Skip to content

Commit

Permalink
Fix too small loop variables (#2829)
Browse files Browse the repository at this point in the history
Fix issues reported by run-clang-tidy -header-filter='.*' -checks='-*,bugprone-too-small-loop-variable'
  • Loading branch information
SunBlack authored and SergioRAgostinho committed Feb 8, 2019
1 parent b535651 commit 1cb184d
Show file tree
Hide file tree
Showing 119 changed files with 360 additions and 360 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ namespace pcl
cloud_out.height = 1;
cloud_out.is_dense = false;

for (int i = 0; i < points->GetNumberOfPoints (); i++)
for (vtkIdType i = 0; i < points->GetNumberOfPoints (); i++)
{
double p[3];
points->GetPoint (i, p);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ pcl::cloud_composer::SelectionEvent::findIndicesInItem (CloudItem* cloud_item, p
vtkIdTypeArray* point_ids = vtkIdTypeArray::SafeDownCast(points_in_item->GetPointData ()->GetArray ("vtkIdFilter_Ids"));

indices->indices.resize (point_ids->GetNumberOfTuples ());
for(int i =0; i < point_ids->GetNumberOfTuples (); ++i)
for(vtkIdType i =0; i < point_ids->GetNumberOfTuples (); ++i)
{
//qDebug () << "id="<<point_ids->GetValue (i);
indices->indices[i] = point_ids->GetValue (i);
Expand Down
6 changes: 3 additions & 3 deletions apps/in_hand_scanner/src/integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ pcl::ihs::Integration::merge (const CloudXYZRGBNormalConstPtr& cloud_data,
// Nearest neighbor search
CloudXYZPtr xyz_model (new CloudXYZ ());
xyz_model->reserve (mesh_model->sizeVertices ());
for (unsigned int i=0; i<mesh_model->sizeVertices (); ++i)
for (size_t i=0; i<mesh_model->sizeVertices (); ++i)
{
const PointIHS& pt = mesh_model->getVertexDataCloud () [i];
xyz_model->push_back (PointXYZ (pt.x, pt.y, pt.z));
Expand Down Expand Up @@ -388,7 +388,7 @@ pcl::ihs::Integration::merge (const CloudXYZRGBNormalConstPtr& cloud_data,
void
pcl::ihs::Integration::age (const MeshPtr& mesh, const bool cleanup) const
{
for (unsigned int i=0; i<mesh->sizeVertices (); ++i)
for (size_t i=0; i<mesh->sizeVertices (); ++i)
{
PointIHS& pt = mesh->getVertexDataCloud () [i];
if (pt.age < max_age_)
Expand Down Expand Up @@ -422,7 +422,7 @@ pcl::ihs::Integration::age (const MeshPtr& mesh, const bool cleanup) const
void
pcl::ihs::Integration::removeUnfitVertices (const MeshPtr& mesh, const bool cleanup) const
{
for (unsigned int i=0; i<mesh->sizeVertices (); ++i)
for (size_t i=0; i<mesh->sizeVertices (); ++i)
{
if (pcl::ihs::countDirections (mesh->getVertexDataCloud () [i].directions) < min_directions_)
{
Expand Down
2 changes: 1 addition & 1 deletion apps/in_hand_scanner/src/offline_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ pcl::ihs::OfflineIntegration::computationThread ()
return;
}

for (unsigned int i=1; i<filenames.size (); ++i)
for (size_t i=1; i<filenames.size (); ++i)
{
std::cerr << "Processing file " << std::setw (5) << i+1 << " / " << filenames.size () << std::endl;

Expand Down
4 changes: 2 additions & 2 deletions apps/in_hand_scanner/src/opengl_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ pcl::ihs::detail::FaceVertexMesh::FaceVertexMesh (const Mesh& mesh, const Eigen:
triangles.reserve (mesh.sizeFaces ());
pcl::ihs::detail::FaceVertexMesh::Triangle triangle;

for (unsigned int i=0; i<mesh.sizeFaces (); ++i)
for (size_t i=0; i<mesh.sizeFaces (); ++i)
{
Mesh::VertexAroundFaceCirculator circ = mesh.getVertexAroundFaceCirculator (Mesh::FaceIndex (i));
triangle.first = (circ++).getTargetIndex ().get ();
Expand Down Expand Up @@ -932,7 +932,7 @@ pcl::ihs::OpenGLViewer::drawMeshes ()
}
case COL_VISCONF:
{
for (unsigned int i=0; i<mesh.vertices.size (); ++i)
for (size_t i=0; i<mesh.vertices.size (); ++i)
{
const unsigned int n = pcl::ihs::countDirections (mesh.vertices [i].directions);
const unsigned int index = static_cast <unsigned int> (
Expand Down
2 changes: 1 addition & 1 deletion apps/in_hand_scanner/src/visibility_confidence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ pcl::ihs::Dome::Dome ()
vertices_.col (29) = Eigen::Vector4f (-0.187592626f, -0.577350378f, 0.794654489f, 0.f);
vertices_.col (30) = Eigen::Vector4f ( 0.491123348f, -0.356822133f, 0.794654548f, 0.f);

for (unsigned int i=0; i<vertices_.cols (); ++i)
for (Eigen::Index i=0; i < vertices_.cols (); ++i)
{
vertices_.col (i).head <3> ().normalize ();
}
Expand Down
4 changes: 2 additions & 2 deletions apps/point_cloud_editor/src/cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -418,7 +418,7 @@ Cloud::getDisplaySpacePoint (unsigned int index) const
void
Cloud::getDisplaySpacePoints (Point3DVector& pts) const
{
for(unsigned int i = 0; i < cloud_.size(); ++i)
for(size_t i = 0; i < cloud_.size(); ++i)
pts.push_back(getDisplaySpacePoint(i));
}

Expand Down Expand Up @@ -464,7 +464,7 @@ Cloud::updateCloudMembers ()
float *pt = &(cloud_.points[0].data[X]);
std::copy(pt, pt+XYZ_SIZE, max_xyz_);
std::copy(max_xyz_, max_xyz_+XYZ_SIZE, min_xyz_);
for (unsigned int i = 1; i < cloud_.size(); ++i)
for (size_t i = 1; i < cloud_.size(); ++i)
{
for (unsigned int j = 0; j < XYZ_SIZE; ++j)
{
Expand Down
2 changes: 1 addition & 1 deletion apps/point_cloud_editor/src/cloudEditorWidget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -573,7 +573,7 @@ CloudEditorWidget::isColored (const std::string &fileName) const
pcl::PCDReader reader;
reader.readHeader(fileName, cloud2);
std::vector< pcl::PCLPointField > fs = cloud2.fields;
for(unsigned int i = 0; i < fs.size(); ++i)
for(size_t i = 0; i < fs.size(); ++i)
{
std::string name(fs[i].name);
stringToLower(name);
Expand Down
2 changes: 1 addition & 1 deletion apps/point_cloud_editor/src/select2DTool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ Select2DTool::end (int x, int y, BitMask modifiers, BitMask)

Point3DVector ptsvec;
cloud_ptr_->getDisplaySpacePoints(ptsvec);
for(unsigned int i = 0; i < ptsvec.size(); ++i)
for(size_t i = 0; i < ptsvec.size(); ++i)
{
Point3D pt = ptsvec[i];
if (isInSelectBox(pt, project, viewport))
Expand Down
2 changes: 1 addition & 1 deletion apps/src/convolve.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ main (int argc, char ** argv)
Eigen::ArrayXf gaussian_kernel(5);
gaussian_kernel << 1.f/16, 1.f/4, 3.f/8, 1.f/4, 1.f/16;
pcl::console::print_info ("convolution kernel:");
for (int i = 0; i < gaussian_kernel.size (); ++i)
for (Eigen::Index i = 0; i < gaussian_kernel.size (); ++i)
pcl::console::print_info (" %f", gaussian_kernel[i]);
pcl::console::print_info ("\n");

Expand Down
4 changes: 2 additions & 2 deletions apps/src/feature_matching.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,12 +298,12 @@ void ICCVTutorial<FeatureType>::filterCorrespondences ()
{
cout << "correspondence rejection..." << std::flush;
std::vector<std::pair<unsigned, unsigned> > correspondences;
for (unsigned cIdx = 0; cIdx < source2target_.size (); ++cIdx)
for (size_t cIdx = 0; cIdx < source2target_.size (); ++cIdx)
if (target2source_[source2target_[cIdx]] == static_cast<int> (cIdx))
correspondences.push_back(std::make_pair(cIdx, source2target_[cIdx]));

correspondences_->resize (correspondences.size());
for (unsigned cIdx = 0; cIdx < correspondences.size(); ++cIdx)
for (size_t cIdx = 0; cIdx < correspondences.size(); ++cIdx)
{
(*correspondences_)[cIdx].index_query = correspondences[cIdx].first;
(*correspondences_)[cIdx].index_match = correspondences[cIdx].second;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/nn_classification_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ main (int, char* argv[])
}

// Print results
for (unsigned i = 0; i < result->first.size(); ++i)
for (size_t i = 0; i < result->first.size(); ++i)
std::cerr << result->first.at (i) << ": " << result->second.at (i) << std::endl;

return 0;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/pcd_organized_multi_plane_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ class PCDOrganizedMultiPlaneSegmentation

// sprintf (name, "approx_plane_%02d", int (i));
// viewer.addPolygon<PointT> (approx_contour_const, 0.5 * red[i], 0.5 * grn[i], 0.5 * blu[i], name);
for (unsigned idx = 0; idx < approx_contour->points.size (); ++idx)
for (size_t idx = 0; idx < approx_contour->points.size (); ++idx)
{
sprintf (name, "approx_plane_%02d_%03d", int (i), int(idx));
viewer.addLine (approx_contour->points [idx], approx_contour->points [(idx+1)%approx_contour->points.size ()], 0.5 * red[i], 0.5 * grn[i], 0.5 * blu[i], name);
Expand Down
4 changes: 2 additions & 2 deletions apps/src/render_views_tesselated_sphere.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() {
else
{
cam_positions.resize (sphere->GetNumberOfPoints ());
for (int i = 0; i < sphere->GetNumberOfPoints (); i++)
for (vtkIdType i = 0; i < sphere->GetNumberOfPoints (); i++)
{
double cam_pos[3];
sphere->GetPoint (i, cam_pos);
Expand Down Expand Up @@ -382,7 +382,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() {
vtkSmartPointer<vtkIdTypeArray> ids = vtkSmartPointer<vtkIdTypeArray>::New ();
ids = vtkIdTypeArray::SafeDownCast(hdw_selection->GetNode(0)->GetSelectionList());
double visible_area = 0;
for (int sel_id = 0; sel_id < (ids->GetNumberOfTuples ()); sel_id++)
for (vtkIdType sel_id = 0; sel_id < (ids->GetNumberOfTuples ()); sel_id++)
{
int id_mesh = int (ids->GetValue (sel_id));
if(id_mesh >= polydata->GetNumberOfPolys())
Expand Down
4 changes: 2 additions & 2 deletions apps/src/test_search.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ main (int argc, char ** argv)
else
{
cloud->resize (1000000);
for (unsigned idx = 0; idx < cloud->size (); ++idx)
for (size_t idx = 0; idx < cloud->size (); ++idx)
{
(*cloud)[idx].x = static_cast<float> (rand () / RAND_MAX);
(*cloud)[idx].y = static_cast<float> (rand () / RAND_MAX);
Expand Down Expand Up @@ -125,7 +125,7 @@ main (int argc, char ** argv)
else
{
cerr << "size of result: " <<kd_indices.size () << endl;
for (unsigned idx = 0; idx < kd_indices.size (); ++idx)
for (size_t idx = 0; idx < kd_indices.size (); ++idx)
{
if (kd_indices[idx] != bf_indices[idx] && kd_distances[idx] != bf_distances[idx])
{
Expand Down
4 changes: 2 additions & 2 deletions common/src/range_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -345,7 +345,7 @@ RangeImage::getIntegralImage (float*& integral_image, int*& valid_points_num_ima
void
RangeImage::setUnseenToMaxRange ()
{
for (unsigned int i=0; i<points.size (); ++i)
for (size_t i=0; i < points.size (); ++i)
if (std::isinf (points[i].range))
points[i].range = std::numeric_limits<float>::infinity ();
}
Expand Down Expand Up @@ -443,7 +443,7 @@ RangeImage::getMinMaxRanges (float& min_range, float& max_range) const
{
min_range = std::numeric_limits<float>::infinity ();
max_range = -std::numeric_limits<float>::infinity ();
for (unsigned int i=0; i<points.size (); ++i)
for (size_t i=0; i < points.size (); ++i)
{
float range = points[i].range;
if (!std::isfinite (range))
Expand Down
4 changes: 2 additions & 2 deletions examples/geometry/example_half_edge_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void
printVertices (const Mesh& mesh)
{
std::cout << "Vertices:\n ";
for (unsigned int i=0; i<mesh.sizeVertices (); ++i)
for (size_t i=0; i<mesh.sizeVertices (); ++i)
{
std::cout << mesh.getVertexDataCloud () [i] << " ";
}
Expand Down Expand Up @@ -132,7 +132,7 @@ void
printFaces (const Mesh& mesh)
{
std::cout << "Faces:\n";
for (unsigned int i=0; i<mesh.sizeFaces (); ++i)
for (size_t i=0; i<mesh.sizeFaces (); ++i)
{
printFace (mesh, FaceIndex (i));
}
Expand Down
2 changes: 1 addition & 1 deletion examples/segmentation/example_supervoxels.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -501,7 +501,7 @@ addSupervoxelConnectionsToViewer (PointT &supervoxel_center,
// Add the points to the dataset
polyData->SetPoints (points);
polyLine->GetPointIds ()->SetNumberOfIds(points->GetNumberOfPoints ());
for(unsigned int i = 0; i < points->GetNumberOfPoints (); i++)
for(vtkIdType i = 0; i < points->GetNumberOfPoints (); i++)
polyLine->GetPointIds ()->SetId (i,i);
cells->InsertNextCell (polyLine);
// Add the lines to the dataset
Expand Down
2 changes: 1 addition & 1 deletion examples/surface/example_nurbs_fitting_closed_curve.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ pcl::visualization::PCLVisualizer viewer ("Curve Fitting PDM (red), SDM (green),
void
PointCloud2Vector2d (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::on_nurbs::vector_vec2d &data)
{
for (unsigned i = 0; i < cloud->size (); i++)
for (size_t i = 0; i < cloud->size (); i++)
{
pcl::PointXYZ &p = cloud->at (i);
if (!std::isnan (p.x) && !std::isnan (p.y))
Expand Down
2 changes: 1 addition & 1 deletion examples/surface/example_nurbs_fitting_closed_curve3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ pcl::visualization::PCLVisualizer viewer ("Curve Fitting 3D");
void
PointCloud2Vector2d (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::on_nurbs::vector_vec3d &data)
{
for (unsigned i = 0; i < cloud->size (); i++)
for (size_t i = 0; i < cloud->size (); i++)
{
pcl::PointXYZ &p = cloud->at (i);
if (!std::isnan (p.x) && !std::isnan (p.y) && !std::isnan (p.z))
Expand Down
4 changes: 2 additions & 2 deletions examples/surface/example_nurbs_fitting_curve2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ pcl::visualization::PCLVisualizer viewer ("Curve Fitting 2D");
void
PointCloud2Vector2d (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::on_nurbs::vector_vec2d &data)
{
for (unsigned i = 0; i < cloud->size (); i++)
for (size_t i = 0; i < cloud->size (); i++)
{
pcl::PointXYZ &p = cloud->at (i);
if (!std::isnan (p.x) && !std::isnan (p.y))
Expand All @@ -26,7 +26,7 @@ VisualizeCurve (ON_NurbsCurve &curve, double r, double g, double b, bool show_cp
pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
pcl::on_nurbs::Triangulation::convertCurve2PointCloud (curve, cloud, 8);

for (std::size_t i = 0; i < cloud->size () - 1; i++)
for (size_t i = 0; i < cloud->size () - 1; i++)
{
pcl::PointXYZRGB &p1 = cloud->at (i);
pcl::PointXYZRGB &p2 = cloud->at (i + 1);
Expand Down
2 changes: 1 addition & 1 deletion examples/surface/example_nurbs_fitting_surface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ main (int argc, char *argv[])
void
PointCloud2Vector3d (pcl::PointCloud<Point>::Ptr cloud, pcl::on_nurbs::vector_vec3d &data)
{
for (unsigned i = 0; i < cloud->size (); i++)
for (size_t i = 0; i < cloud->size (); i++)
{
Point &p = cloud->at (i);
if (!std::isnan (p.x) && !std::isnan (p.y) && !std::isnan (p.z))
Expand Down
8 changes: 4 additions & 4 deletions features/include/pcl/features/impl/fpfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@ pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
{
if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
{
for (int d = 0; d < fpfh_histogram_.size (); ++d)
for (size_t d = 0; d < fpfh_histogram_.size (); ++d)
output.points[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();

output.is_dense = false;
Expand All @@ -266,7 +266,7 @@ pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);

// ...and copy it into the output cloud
for (int d = 0; d < fpfh_histogram_.size (); ++d)
for (size_t d = 0; d < fpfh_histogram_.size (); ++d)
output.points[idx].histogram[d] = fpfh_histogram_[d];
}
}
Expand All @@ -278,7 +278,7 @@ pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
if (!isFinite ((*input_)[(*indices_)[idx]]) ||
this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
{
for (int d = 0; d < fpfh_histogram_.size (); ++d)
for (size_t d = 0; d < fpfh_histogram_.size (); ++d)
output.points[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();

output.is_dense = false;
Expand All @@ -294,7 +294,7 @@ pcl::FPFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);

// ...and copy it into the output cloud
for (int d = 0; d < fpfh_histogram_.size (); ++d)
for (size_t d = 0; d < fpfh_histogram_.size (); ++d)
output.points[idx].histogram[d] = fpfh_histogram_[d];
}
}
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/grsd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ pcl::GRSDEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
{
int source_type = types[idx];
std::vector<int> neighbors = grid.getNeighborCentroidIndices (cloud_downsampled->points[idx], relative_coordinates_all_);
for (unsigned id_n = 0; id_n < neighbors.size (); id_n++)
for (size_t id_n = 0; id_n < neighbors.size (); id_n++)
{
int neighbor_type;
if (neighbors[id_n] == -1) // empty
Expand Down
6 changes: 3 additions & 3 deletions features/include/pcl/features/impl/intensity_spin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,9 +161,9 @@ pcl::IntensitySpinEstimation<PointInT, PointOutT>::computeFeature (PointCloudOut
computeIntensitySpinImage (*surface_, static_cast<float> (search_radius_), sigma_, k, nn_indices, nn_dist_sqr, intensity_spin_image);

// Copy into the resultant cloud
int bin = 0;
for (int bin_j = 0; bin_j < intensity_spin_image.cols (); ++bin_j)
for (int bin_i = 0; bin_i < intensity_spin_image.rows (); ++bin_i)
size_t bin = 0;
for (Eigen::Index bin_j = 0; bin_j < intensity_spin_image.cols (); ++bin_j)
for (Eigen::Index bin_i = 0; bin_i < intensity_spin_image.rows (); ++bin_i)
output.points[idx].histogram[bin++] = intensity_spin_image (bin_i, bin_j);
}
}
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/normal_based_signature.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,10 +143,10 @@ pcl::NormalBasedSignatureEstimation<PointT, PointNT, PointFeature>::computeFeatu

// do DCT on the s_matrix row-wise
Eigen::VectorXf dct_row (M_);
for (int m = 0; m < s_row.size (); ++m)
for (Eigen::Index m = 0; m < s_row.size (); ++m)
{
float Xk = 0.0f;
for (int n = 0; n < s_row.size (); ++n)
for (Eigen::Index n = 0; n < s_row.size (); ++n)
Xk += static_cast<float> (s_row[n] * cos (M_PI / (static_cast<double> (M_ * n) + 0.5) * static_cast<double> (k)));
dct_row[m] = Xk;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ pcl::OrganizedEdgeBase<PointT, PointLT>::assignLabelIndices (pcl::PointCloud<Poi
{
const unsigned invalid_label = unsigned (0);
label_indices.resize (num_of_edgetype_);
for (unsigned idx = 0; idx < input_->points.size (); idx++)
for (size_t idx = 0; idx < input_->points.size (); idx++)
{
if (labels[idx].label != invalid_label)
{
Expand Down
Loading

0 comments on commit 1cb184d

Please sign in to comment.