From 1cb184d7824ae45cb7d67a63e3897451b00049f1 Mon Sep 17 00:00:00 2001 From: SunBlack Date: Fri, 8 Feb 2019 10:04:01 +0100 Subject: [PATCH] Fix too small loop variables (#2829) Fix issues reported by run-clang-tidy -header-filter='.*' -checks='-*,bugprone-too-small-loop-variable' --- .../utils/vtk_model_sampling.h | 2 +- .../src/point_selectors/selection_event.cpp | 2 +- apps/in_hand_scanner/src/integration.cpp | 6 ++--- .../src/offline_integration.cpp | 2 +- apps/in_hand_scanner/src/opengl_viewer.cpp | 4 ++-- .../src/visibility_confidence.cpp | 2 +- apps/point_cloud_editor/src/cloud.cpp | 4 ++-- .../src/cloudEditorWidget.cpp | 2 +- apps/point_cloud_editor/src/select2DTool.cpp | 2 +- apps/src/convolve.cpp | 2 +- apps/src/feature_matching.cpp | 4 ++-- apps/src/nn_classification_example.cpp | 2 +- ...pcd_organized_multi_plane_segmentation.cpp | 2 +- apps/src/render_views_tesselated_sphere.cpp | 4 ++-- apps/src/test_search.cpp | 4 ++-- common/src/range_image.cpp | 4 ++-- examples/geometry/example_half_edge_mesh.cpp | 4 ++-- examples/segmentation/example_supervoxels.cpp | 2 +- .../example_nurbs_fitting_closed_curve.cpp | 2 +- .../example_nurbs_fitting_closed_curve3d.cpp | 2 +- .../surface/example_nurbs_fitting_curve2d.cpp | 4 ++-- .../surface/example_nurbs_fitting_surface.cpp | 2 +- features/include/pcl/features/impl/fpfh.hpp | 8 +++---- features/include/pcl/features/impl/grsd.hpp | 2 +- .../pcl/features/impl/intensity_spin.hpp | 6 ++--- .../features/impl/normal_based_signature.hpp | 4 ++-- .../impl/organized_edge_detection.hpp | 2 +- features/include/pcl/features/impl/pfh.hpp | 8 +++---- features/include/pcl/features/impl/pfhrgb.hpp | 2 +- features/include/pcl/features/impl/rift.hpp | 6 ++--- .../include/pcl/features/impl/shot_omp.hpp | 8 +++---- .../include/pcl/features/impl/spin_image.hpp | 4 ++-- features/include/pcl/features/impl/vfh.hpp | 10 ++++---- features/src/narf.cpp | 8 +++---- .../pcl/filters/impl/box_clipper3D.hpp | 2 +- .../include/pcl/filters/impl/grid_minimum.hpp | 2 +- .../include/pcl/filters/impl/normal_space.hpp | 14 +++++------ .../filters/impl/sampling_surface_normal.hpp | 14 +++++------ .../include/pcl/filters/impl/shadowpoints.hpp | 8 +++---- .../include/pcl/filters/impl/voxel_grid.hpp | 2 +- .../filters/impl/voxel_grid_covariance.hpp | 2 +- .../pcl/filters/model_outlier_removal.h | 4 ++-- .../include/pcl/filters/normal_refinement.h | 2 +- filters/include/pcl/filters/voxel_grid.h | 4 ++-- .../pcl/geometry/impl/polygon_operations.hpp | 20 ++++++++-------- geometry/include/pcl/geometry/mesh_base.h | 8 +++---- gpu/kinfu_large_scale/src/cyclical_buffer.cpp | 2 +- .../tools/standalone_texture_mapping.cpp | 8 +++---- gpu/people/src/face_detector.cpp | 8 +++---- gpu/people/src/organized_plane_detector.cpp | 10 ++++---- gpu/people/tools/people_app.cpp | 2 +- .../compression/impl/entropy_range_coder.hpp | 12 +++++----- io/src/openni2_grabber.cpp | 20 ++++++++-------- io/src/openni_camera/openni_driver.cpp | 6 ++--- io/src/vtk_lib_io.cpp | 2 +- .../include/pcl/keypoints/impl/harris_3d.hpp | 2 +- .../include/pcl/keypoints/impl/harris_6d.hpp | 2 +- .../include/pcl/keypoints/impl/iss_3d.hpp | 2 +- ml/src/densecrf.cpp | 2 +- .../main_ground_based_people_detection.cpp | 2 +- .../pcl/people/impl/head_based_subcluster.hpp | 10 ++++---- .../pcl/people/impl/person_classifier.hpp | 2 +- .../recognition/impl/implicit_shape_model.hpp | 16 ++++++------- .../include/pcl/registration/impl/ndt.hpp | 4 ++-- .../impl/sac_model_circle3d.hpp | 2 +- .../include/pcl/sample_consensus/sac_model.h | 8 +++---- .../include/pcl/search/impl/brute_force.hpp | 4 ++-- .../euclidean_cluster_comparator.h | 2 +- ...nized_connected_component_segmentation.hpp | 8 +++---- .../organized_multi_plane_segmentation.hpp | 8 +++---- .../pcl/segmentation/impl/random_walker.hpp | 8 +++---- surface/include/pcl/surface/impl/gp3.hpp | 2 +- surface/include/pcl/surface/impl/mls.hpp | 4 ++-- .../pcl/surface/impl/organized_fast_mesh.hpp | 2 +- surface/src/on_nurbs/closing_boundary.cpp | 14 +++++------ surface/src/on_nurbs/fitting_curve_2d.cpp | 14 +++++------ .../src/on_nurbs/fitting_curve_2d_apdm.cpp | 24 +++++++++---------- .../src/on_nurbs/fitting_curve_2d_asdm.cpp | 2 +- .../src/on_nurbs/fitting_curve_2d_atdm.cpp | 2 +- surface/src/on_nurbs/fitting_curve_2d_pdm.cpp | 18 +++++++------- surface/src/on_nurbs/fitting_curve_pdm.cpp | 8 +++---- surface/src/on_nurbs/fitting_cylinder_pdm.cpp | 12 +++++----- surface/src/on_nurbs/fitting_sphere_pdm.cpp | 6 ++--- surface/src/on_nurbs/fitting_surface_im.cpp | 8 +++---- surface/src/on_nurbs/fitting_surface_pdm.cpp | 18 +++++++------- .../src/on_nurbs/global_optimization_pdm.cpp | 18 +++++++------- .../src/on_nurbs/global_optimization_tdm.cpp | 14 +++++------ surface/src/on_nurbs/nurbs_solve_eigen.cpp | 12 +++++----- surface/src/on_nurbs/nurbs_tools.cpp | 12 +++++----- surface/src/on_nurbs/sequential_fitter.cpp | 6 ++--- surface/src/on_nurbs/triangulation.cpp | 12 +++++----- surface/src/vtk_smoothing/vtk_utils.cpp | 2 +- test/common/test_gaussian.cpp | 6 ++--- test/common/test_vector_average.cpp | 4 ++-- test/features/test_gasd_estimation.cpp | 4 ++-- test/features/test_narf.cpp | 2 +- test/filters/test_filters.cpp | 10 ++++---- test/geometry/test_mesh.cpp | 24 +++++++++---------- test/geometry/test_mesh_circulators.cpp | 12 +++++----- test/geometry/test_mesh_common_functions.h | 8 +++---- test/geometry/test_mesh_data.cpp | 8 +++---- test/geometry/test_polygon_mesh.cpp | 2 +- test/geometry/test_quad_mesh.cpp | 8 +++---- test/geometry/test_triangle_mesh.cpp | 4 ++-- test/io/test_ply_io.cpp | 2 +- test/kdtree/test_kdtree.cpp | 2 +- test/octree/test_octree.cpp | 8 +++---- .../test_correspondence_estimation.cpp | 2 +- .../test_correspondence_rejectors.cpp | 6 ++--- .../test_sample_consensus_plane_models.cpp | 2 +- test/search/test_search.cpp | 6 ++--- test/segmentation/test_random_walker.cpp | 4 ++-- tools/tiff2pcd.cpp | 2 +- visualization/src/common/io.cpp | 2 +- visualization/src/image_viewer.cpp | 4 ++-- visualization/src/pcl_plotter.cpp | 2 +- visualization/src/pcl_visualizer.cpp | 6 ++--- visualization/src/range_image_visualizer.cpp | 2 +- visualization/tools/openni2_viewer.cpp | 2 +- 119 files changed, 360 insertions(+), 360 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/vtk_model_sampling.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/vtk_model_sampling.h index 349539cbb70..dd63efdbf65 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/vtk_model_sampling.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/vtk_model_sampling.h @@ -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); diff --git a/apps/cloud_composer/src/point_selectors/selection_event.cpp b/apps/cloud_composer/src/point_selectors/selection_event.cpp index 4f1e295c047..aeeef4cfc99 100644 --- a/apps/cloud_composer/src/point_selectors/selection_event.cpp +++ b/apps/cloud_composer/src/point_selectors/selection_event.cpp @@ -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="<GetValue (i); indices->indices[i] = point_ids->GetValue (i); diff --git a/apps/in_hand_scanner/src/integration.cpp b/apps/in_hand_scanner/src/integration.cpp index 25dbc50e103..4deff04a7ed 100644 --- a/apps/in_hand_scanner/src/integration.cpp +++ b/apps/in_hand_scanner/src/integration.cpp @@ -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; isizeVertices (); ++i) + for (size_t i=0; isizeVertices (); ++i) { const PointIHS& pt = mesh_model->getVertexDataCloud () [i]; xyz_model->push_back (PointXYZ (pt.x, pt.y, pt.z)); @@ -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; isizeVertices (); ++i) + for (size_t i=0; isizeVertices (); ++i) { PointIHS& pt = mesh->getVertexDataCloud () [i]; if (pt.age < max_age_) @@ -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; isizeVertices (); ++i) + for (size_t i=0; isizeVertices (); ++i) { if (pcl::ihs::countDirections (mesh->getVertexDataCloud () [i].directions) < min_directions_) { diff --git a/apps/in_hand_scanner/src/offline_integration.cpp b/apps/in_hand_scanner/src/offline_integration.cpp index 7e71536baf4..5088421c2b8 100644 --- a/apps/in_hand_scanner/src/offline_integration.cpp +++ b/apps/in_hand_scanner/src/offline_integration.cpp @@ -146,7 +146,7 @@ pcl::ihs::OfflineIntegration::computationThread () return; } - for (unsigned int i=1; i ( diff --git a/apps/in_hand_scanner/src/visibility_confidence.cpp b/apps/in_hand_scanner/src/visibility_confidence.cpp index 90ebfd6ac7d..6951d580557 100644 --- a/apps/in_hand_scanner/src/visibility_confidence.cpp +++ b/apps/in_hand_scanner/src/visibility_confidence.cpp @@ -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 ().normalize (); } diff --git a/apps/point_cloud_editor/src/cloud.cpp b/apps/point_cloud_editor/src/cloud.cpp index 6392e10070d..5972066d501 100644 --- a/apps/point_cloud_editor/src/cloud.cpp +++ b/apps/point_cloud_editor/src/cloud.cpp @@ -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)); } @@ -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) { diff --git a/apps/point_cloud_editor/src/cloudEditorWidget.cpp b/apps/point_cloud_editor/src/cloudEditorWidget.cpp index 19688348bf6..5dbf9c2a5a1 100644 --- a/apps/point_cloud_editor/src/cloudEditorWidget.cpp +++ b/apps/point_cloud_editor/src/cloudEditorWidget.cpp @@ -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); diff --git a/apps/point_cloud_editor/src/select2DTool.cpp b/apps/point_cloud_editor/src/select2DTool.cpp index 1bf5e05238a..fd780b4c55b 100644 --- a/apps/point_cloud_editor/src/select2DTool.cpp +++ b/apps/point_cloud_editor/src/select2DTool.cpp @@ -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)) diff --git a/apps/src/convolve.cpp b/apps/src/convolve.cpp index f7638410b81..12b22031856 100644 --- a/apps/src/convolve.cpp +++ b/apps/src/convolve.cpp @@ -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"); diff --git a/apps/src/feature_matching.cpp b/apps/src/feature_matching.cpp index a7c824942fa..598bd97ca05 100644 --- a/apps/src/feature_matching.cpp +++ b/apps/src/feature_matching.cpp @@ -298,12 +298,12 @@ void ICCVTutorial::filterCorrespondences () { cout << "correspondence rejection..." << std::flush; std::vector > correspondences; - for (unsigned cIdx = 0; cIdx < source2target_.size (); ++cIdx) + for (size_t cIdx = 0; cIdx < source2target_.size (); ++cIdx) if (target2source_[source2target_[cIdx]] == static_cast (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; diff --git a/apps/src/nn_classification_example.cpp b/apps/src/nn_classification_example.cpp index 8aa09f80aa6..41b0eb3c4cb 100644 --- a/apps/src/nn_classification_example.cpp +++ b/apps/src/nn_classification_example.cpp @@ -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; diff --git a/apps/src/pcd_organized_multi_plane_segmentation.cpp b/apps/src/pcd_organized_multi_plane_segmentation.cpp index 954a8653162..8744ee372ca 100644 --- a/apps/src/pcd_organized_multi_plane_segmentation.cpp +++ b/apps/src/pcd_organized_multi_plane_segmentation.cpp @@ -186,7 +186,7 @@ class PCDOrganizedMultiPlaneSegmentation // sprintf (name, "approx_plane_%02d", int (i)); // viewer.addPolygon (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); diff --git a/apps/src/render_views_tesselated_sphere.cpp b/apps/src/render_views_tesselated_sphere.cpp index a4c9a55132c..b5f666bf873 100644 --- a/apps/src/render_views_tesselated_sphere.cpp +++ b/apps/src/render_views_tesselated_sphere.cpp @@ -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); @@ -382,7 +382,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() { vtkSmartPointer ids = vtkSmartPointer::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()) diff --git a/apps/src/test_search.cpp b/apps/src/test_search.cpp index ba2fd87b447..cf2ec07b368 100644 --- a/apps/src/test_search.cpp +++ b/apps/src/test_search.cpp @@ -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 (rand () / RAND_MAX); (*cloud)[idx].y = static_cast (rand () / RAND_MAX); @@ -125,7 +125,7 @@ main (int argc, char ** argv) else { cerr << "size of result: " <::infinity (); } @@ -443,7 +443,7 @@ RangeImage::getMinMaxRanges (float& min_range, float& max_range) const { min_range = std::numeric_limits::infinity (); max_range = -std::numeric_limits::infinity (); - for (unsigned int i=0; iSetPoints (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 diff --git a/examples/surface/example_nurbs_fitting_closed_curve.cpp b/examples/surface/example_nurbs_fitting_closed_curve.cpp index 8b29f890140..1fdd188f3b2 100644 --- a/examples/surface/example_nurbs_fitting_closed_curve.cpp +++ b/examples/surface/example_nurbs_fitting_closed_curve.cpp @@ -14,7 +14,7 @@ pcl::visualization::PCLVisualizer viewer ("Curve Fitting PDM (red), SDM (green), void PointCloud2Vector2d (pcl::PointCloud::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)) diff --git a/examples/surface/example_nurbs_fitting_closed_curve3d.cpp b/examples/surface/example_nurbs_fitting_closed_curve3d.cpp index 572a38e1c0a..3b5b38608e3 100644 --- a/examples/surface/example_nurbs_fitting_closed_curve3d.cpp +++ b/examples/surface/example_nurbs_fitting_closed_curve3d.cpp @@ -12,7 +12,7 @@ pcl::visualization::PCLVisualizer viewer ("Curve Fitting 3D"); void PointCloud2Vector2d (pcl::PointCloud::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)) diff --git a/examples/surface/example_nurbs_fitting_curve2d.cpp b/examples/surface/example_nurbs_fitting_curve2d.cpp index 99d9375fb73..89e81439c6e 100644 --- a/examples/surface/example_nurbs_fitting_curve2d.cpp +++ b/examples/surface/example_nurbs_fitting_curve2d.cpp @@ -12,7 +12,7 @@ pcl::visualization::PCLVisualizer viewer ("Curve Fitting 2D"); void PointCloud2Vector2d (pcl::PointCloud::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)) @@ -26,7 +26,7 @@ VisualizeCurve (ON_NurbsCurve &curve, double r, double g, double b, bool show_cp pcl::PointCloud::Ptr cloud (new pcl::PointCloud); 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); diff --git a/examples/surface/example_nurbs_fitting_surface.cpp b/examples/surface/example_nurbs_fitting_surface.cpp index 2bcb0a174b6..7fb67fc79e9 100644 --- a/examples/surface/example_nurbs_fitting_surface.cpp +++ b/examples/surface/example_nurbs_fitting_surface.cpp @@ -171,7 +171,7 @@ main (int argc, char *argv[]) void PointCloud2Vector3d (pcl::PointCloud::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)) diff --git a/features/include/pcl/features/impl/fpfh.hpp b/features/include/pcl/features/impl/fpfh.hpp index 8a4a89dd422..5c106ffdde8 100644 --- a/features/include/pcl/features/impl/fpfh.hpp +++ b/features/include/pcl/features/impl/fpfh.hpp @@ -250,7 +250,7 @@ pcl::FPFHEstimation::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::quiet_NaN (); output.is_dense = false; @@ -266,7 +266,7 @@ pcl::FPFHEstimation::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]; } } @@ -278,7 +278,7 @@ pcl::FPFHEstimation::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::quiet_NaN (); output.is_dense = false; @@ -294,7 +294,7 @@ pcl::FPFHEstimation::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]; } } diff --git a/features/include/pcl/features/impl/grsd.hpp b/features/include/pcl/features/impl/grsd.hpp index 5736f8f1981..b4bc1ecdffd 100644 --- a/features/include/pcl/features/impl/grsd.hpp +++ b/features/include/pcl/features/impl/grsd.hpp @@ -102,7 +102,7 @@ pcl::GRSDEstimation::computeFeature (PointCloudOut { int source_type = types[idx]; std::vector 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 diff --git a/features/include/pcl/features/impl/intensity_spin.hpp b/features/include/pcl/features/impl/intensity_spin.hpp index 9e690c93898..ba5b949cc5b 100644 --- a/features/include/pcl/features/impl/intensity_spin.hpp +++ b/features/include/pcl/features/impl/intensity_spin.hpp @@ -161,9 +161,9 @@ pcl::IntensitySpinEstimation::computeFeature (PointCloudOut computeIntensitySpinImage (*surface_, static_cast (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); } } diff --git a/features/include/pcl/features/impl/normal_based_signature.hpp b/features/include/pcl/features/impl/normal_based_signature.hpp index 08d97e39179..15cd4bcba16 100644 --- a/features/include/pcl/features/impl/normal_based_signature.hpp +++ b/features/include/pcl/features/impl/normal_based_signature.hpp @@ -143,10 +143,10 @@ pcl::NormalBasedSignatureEstimation::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 (s_row[n] * cos (M_PI / (static_cast (M_ * n) + 0.5) * static_cast (k))); dct_row[m] = Xk; } diff --git a/features/include/pcl/features/impl/organized_edge_detection.hpp b/features/include/pcl/features/impl/organized_edge_detection.hpp index 6d22a7523b9..1962309393f 100644 --- a/features/include/pcl/features/impl/organized_edge_detection.hpp +++ b/features/include/pcl/features/impl/organized_edge_detection.hpp @@ -70,7 +70,7 @@ pcl::OrganizedEdgeBase::assignLabelIndices (pcl::PointCloudpoints.size (); idx++) + for (size_t idx = 0; idx < input_->points.size (); idx++) { if (labels[idx].label != invalid_label) { diff --git a/features/include/pcl/features/impl/pfh.hpp b/features/include/pcl/features/impl/pfh.hpp index 5171f7f46c8..024264a6766 100644 --- a/features/include/pcl/features/impl/pfh.hpp +++ b/features/include/pcl/features/impl/pfh.hpp @@ -184,7 +184,7 @@ pcl::PFHEstimation::computeFeature (PointCloudOut { if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) { - for (int d = 0; d < pfh_histogram_.size (); ++d) + for (Eigen::Index d = 0; d < pfh_histogram_.size (); ++d) output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); output.is_dense = false; @@ -195,7 +195,7 @@ pcl::PFHEstimation::computeFeature (PointCloudOut computePointPFHSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfh_histogram_); // Copy into the resultant cloud - for (int d = 0; d < pfh_histogram_.size (); ++d) + for (Eigen::Index d = 0; d < pfh_histogram_.size (); ++d) output.points[idx].histogram[d] = pfh_histogram_[d]; } } @@ -207,7 +207,7 @@ pcl::PFHEstimation::computeFeature (PointCloudOut if (!isFinite ((*input_)[(*indices_)[idx]]) || this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) { - for (int d = 0; d < pfh_histogram_.size (); ++d) + for (Eigen::Index d = 0; d < pfh_histogram_.size (); ++d) output.points[idx].histogram[d] = std::numeric_limits::quiet_NaN (); output.is_dense = false; @@ -218,7 +218,7 @@ pcl::PFHEstimation::computeFeature (PointCloudOut computePointPFHSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfh_histogram_); // Copy into the resultant cloud - for (int d = 0; d < pfh_histogram_.size (); ++d) + for (Eigen::Index d = 0; d < pfh_histogram_.size (); ++d) output.points[idx].histogram[d] = pfh_histogram_[d]; } } diff --git a/features/include/pcl/features/impl/pfhrgb.hpp b/features/include/pcl/features/impl/pfhrgb.hpp index bbbb1dad8a7..889152c26fd 100644 --- a/features/include/pcl/features/impl/pfhrgb.hpp +++ b/features/include/pcl/features/impl/pfhrgb.hpp @@ -160,7 +160,7 @@ pcl::PFHRGBEstimation::computeFeature (PointCloudO computePointPFHRGBSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfhrgb_histogram_); // Copy into the resultant cloud - for (int d = 0; d < pfhrgb_histogram_.size (); ++d) { + for (Eigen::Index d = 0; d < pfhrgb_histogram_.size (); ++d) { output.points[idx].histogram[d] = pfhrgb_histogram_[d]; // PCL_INFO ("%f ", pfhrgb_histogram_[d]); } diff --git a/features/include/pcl/features/impl/rift.hpp b/features/include/pcl/features/impl/rift.hpp index 3f10a8be7ca..02919122f6e 100644 --- a/features/include/pcl/features/impl/rift.hpp +++ b/features/include/pcl/features/impl/rift.hpp @@ -171,9 +171,9 @@ pcl::RIFTEstimation::computeFeature (PointCloudO computeRIFT (*surface_, *gradient_, (*indices_)[idx], static_cast (search_radius_), nn_indices, nn_dist_sqr, rift_descriptor); // Copy into the resultant cloud - int bin = 0; - for (int g_bin = 0; g_bin < rift_descriptor.cols (); ++g_bin) - for (int d_bin = 0; d_bin < rift_descriptor.rows (); ++d_bin) + size_t bin = 0; + for (Eigen::Index g_bin = 0; g_bin < rift_descriptor.cols (); ++g_bin) + for (Eigen::Index d_bin = 0; d_bin < rift_descriptor.rows (); ++d_bin) output.points[idx].histogram[bin++] = rift_descriptor (d_bin, g_bin); } } diff --git a/features/include/pcl/features/impl/shot_omp.hpp b/features/include/pcl/features/impl/shot_omp.hpp index 038992e8ad8..3bfa9864c6b 100644 --- a/features/include/pcl/features/impl/shot_omp.hpp +++ b/features/include/pcl/features/impl/shot_omp.hpp @@ -179,7 +179,7 @@ pcl::SHOTEstimationOMP::computeFeature ( nn_dists) == 0) { // Copy into the resultant cloud - for (int d = 0; d < shot.size (); ++d) + for (Eigen::Index d = 0; d < shot.size (); ++d) output.points[idx].descriptor[d] = std::numeric_limits::quiet_NaN (); for (int d = 0; d < 9; ++d) output.points[idx].rf[d] = std::numeric_limits::quiet_NaN (); @@ -192,7 +192,7 @@ pcl::SHOTEstimationOMP::computeFeature ( this->computePointSHOT (idx, nn_indices, nn_dists, shot); // Copy into the resultant cloud - for (int d = 0; d < shot.size (); ++d) + for (Eigen::Index d = 0; d < shot.size (); ++d) output.points[idx].descriptor[d] = shot[d]; for (int d = 0; d < 3; ++d) { @@ -267,7 +267,7 @@ pcl::SHOTColorEstimationOMP::computeFeat this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) { // Copy into the resultant cloud - for (int d = 0; d < shot.size (); ++d) + for (Eigen::Index d = 0; d < shot.size (); ++d) output.points[idx].descriptor[d] = std::numeric_limits::quiet_NaN (); for (int d = 0; d < 9; ++d) output.points[idx].rf[d] = std::numeric_limits::quiet_NaN (); @@ -280,7 +280,7 @@ pcl::SHOTColorEstimationOMP::computeFeat this->computePointSHOT (idx, nn_indices, nn_dists, shot); // Copy into the resultant cloud - for (int d = 0; d < shot.size (); ++d) + for (Eigen::Index d = 0; d < shot.size (); ++d) output.points[idx].descriptor[d] = shot[d]; for (int d = 0; d < 3; ++d) { diff --git a/features/include/pcl/features/impl/spin_image.hpp b/features/include/pcl/features/impl/spin_image.hpp index 6d10089f2fb..5fb38f5deed 100644 --- a/features/include/pcl/features/impl/spin_image.hpp +++ b/features/include/pcl/features/impl/spin_image.hpp @@ -328,9 +328,9 @@ pcl::SpinImageEstimation::computeFeature (PointClo Eigen::ArrayXXd res = computeSiForPoint (indices_->at (i_input)); // Copy into the resultant cloud - for (int iRow = 0; iRow < res.rows () ; iRow++) + for (Eigen::Index iRow = 0; iRow < res.rows () ; iRow++) { - for (int iCol = 0; iCol < res.cols () ; iCol++) + for (Eigen::Index iCol = 0; iCol < res.cols () ; iCol++) { output.points[i_input].histogram[ iRow*res.cols () + iCol ] = static_cast (res (iRow, iCol)); } diff --git a/features/include/pcl/features/impl/vfh.hpp b/features/include/pcl/features/impl/vfh.hpp index 12465fdcc39..a6ed27112f2 100644 --- a/features/include/pcl/features/impl/vfh.hpp +++ b/features/include/pcl/features/impl/vfh.hpp @@ -238,19 +238,19 @@ pcl::VFHEstimation::computeFeature (PointCloudOut output.height = 1; // Estimate the FPFH at nn_indices[0] using the entire cloud and copy the resultant signature - for (int d = 0; d < hist_f1_.size (); ++d) + for (Eigen::Index d = 0; d < hist_f1_.size (); ++d) output.points[0].histogram[d + 0] = hist_f1_[d]; size_t data_size = hist_f1_.size (); - for (int d = 0; d < hist_f2_.size (); ++d) + for (Eigen::Index d = 0; d < hist_f2_.size (); ++d) output.points[0].histogram[d + data_size] = hist_f2_[d]; data_size += hist_f2_.size (); - for (int d = 0; d < hist_f3_.size (); ++d) + for (Eigen::Index d = 0; d < hist_f3_.size (); ++d) output.points[0].histogram[d + data_size] = hist_f3_[d]; data_size += hist_f3_.size (); - for (int d = 0; d < hist_f4_.size (); ++d) + for (Eigen::Index d = 0; d < hist_f4_.size (); ++d) output.points[0].histogram[d + data_size] = hist_f4_[d]; // ---[ Step 2 : obtain the viewpoint component @@ -279,7 +279,7 @@ pcl::VFHEstimation::computeFeature (PointCloudOut } data_size += hist_f4_.size (); // Copy the resultant signature - for (int d = 0; d < hist_vp_.size (); ++d) + for (Eigen::Index d = 0; d < hist_vp_.size (); ++d) output.points[0].histogram[d + data_size] = hist_vp_[d]; } diff --git a/features/src/narf.cpp b/features/src/narf.cpp index 65a13d4602e..55018c39e97 100644 --- a/features/src/narf.cpp +++ b/features/src/narf.cpp @@ -261,7 +261,7 @@ Narf::extractFromRangeImageWithBestRotation (const RangeImage& range_image, cons if (rotations.empty()) return false; float best_rotation=rotations[0], best_strength=strengths[0]; - for (unsigned int i=1; i best_strength) { @@ -401,7 +401,7 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud< feature->getRotations(rotations, strengths); { //feature->getRotatedVersions(range_image, rotations, feature_list); - for (unsigned int i=0; i& rotations, std::vector& strengths void Narf::getRotatedVersions (const RangeImage&, const std::vector& rotations, std::vector& features) const { - for (unsigned int i=0; icopyToNarf36(output.points[i]); } diff --git a/filters/include/pcl/filters/impl/box_clipper3D.hpp b/filters/include/pcl/filters/impl/box_clipper3D.hpp index dc55657c8a3..cfdaeab269a 100644 --- a/filters/include/pcl/filters/impl/box_clipper3D.hpp +++ b/filters/include/pcl/filters/impl/box_clipper3D.hpp @@ -202,7 +202,7 @@ pcl::BoxClipper3D::clipPointCloud3D (const pcl::PointCloud& clou if (indices.empty ()) { clipped.reserve (cloud_in.size ()); - for (unsigned pIdx = 0; pIdx < cloud_in.size (); ++pIdx) + for (size_t pIdx = 0; pIdx < cloud_in.size (); ++pIdx) if (clipPoint3D (cloud_in[pIdx])) clipped.push_back (pIdx); } diff --git a/filters/include/pcl/filters/impl/grid_minimum.hpp b/filters/include/pcl/filters/impl/grid_minimum.hpp index f578245fc8e..c4158726ce9 100644 --- a/filters/include/pcl/filters/impl/grid_minimum.hpp +++ b/filters/include/pcl/filters/impl/grid_minimum.hpp @@ -165,7 +165,7 @@ pcl::GridMinimum::applyFilterIndices (std::vector &indices) index = 0; - for (unsigned int cp = 0; cp < first_and_last_indices_vector.size (); ++cp) + for (size_t cp = 0; cp < first_and_last_indices_vector.size (); ++cp) { unsigned int first_index = first_and_last_indices_vector[cp].first; unsigned int last_index = first_and_last_indices_vector[cp].second; diff --git a/filters/include/pcl/filters/impl/normal_space.hpp b/filters/include/pcl/filters/impl/normal_space.hpp index 64150348d38..a0146d65438 100644 --- a/filters/include/pcl/filters/impl/normal_space.hpp +++ b/filters/include/pcl/filters/impl/normal_space.hpp @@ -206,21 +206,21 @@ pcl::NormalSpaceSampling::applyFilter (std::vector &indice // Setting up random access for the list created above. Maintaining the iterators to individual elements of the list // in a vector. Using vector now as the size of the list is known. std::vector::iterator> > random_access (normals_hg.size ()); - for (unsigned int i = 0; i < normals_hg.size (); i++) + for (size_t i = 0; i < normals_hg.size (); i++) { random_access.emplace_back(); random_access[i].resize (normals_hg[i].size ()); - unsigned int j = 0; + size_t j = 0; for (std::list::iterator itr = normals_hg[i].begin (); itr != normals_hg[i].end (); itr++, j++) random_access[i][j] = itr; } - std::vector start_index (normals_hg.size ()); + std::vector start_index (normals_hg.size ()); start_index[0] = 0; - unsigned int prev_index = start_index[0]; - for (unsigned int i = 1; i < normals_hg.size (); i++) + size_t prev_index = 0; + for (size_t i = 1; i < normals_hg.size (); i++) { - start_index[i] = prev_index + static_cast (normals_hg[i-1].size ()); + start_index[i] = prev_index + normals_hg[i-1].size (); prev_index = start_index[i]; } @@ -232,7 +232,7 @@ pcl::NormalSpaceSampling::applyFilter (std::vector &indice while (i < sample_) { // Iterating through every bin and picking one point at random, until the required number of points are sampled. - for (unsigned int j = 0; j < normals_hg.size (); j++) + for (size_t j = 0; j < normals_hg.size (); j++) { unsigned int M = static_cast (normals_hg[j].size ()); if (M == 0 || bin_empty_flag.test (j)) // bin_empty_flag(i) is set if all points in that bin are sampled.. diff --git a/filters/include/pcl/filters/impl/sampling_surface_normal.hpp b/filters/include/pcl/filters/impl/sampling_surface_normal.hpp index 6ea6fbd7697..72245b193bb 100644 --- a/filters/include/pcl/filters/impl/sampling_surface_normal.hpp +++ b/filters/include/pcl/filters/impl/sampling_surface_normal.hpp @@ -49,7 +49,7 @@ pcl::SamplingSurfaceNormal::applyFilter (PointCloud &output) { std::vector indices; size_t npts = input_->points.size (); - for (unsigned int i = 0; i < npts; i++) + for (size_t i = 0; i < npts; i++) indices.push_back (i); Vector max_vec (3, 1); @@ -68,7 +68,7 @@ pcl::SamplingSurfaceNormal::findXYZMaxMin (const PointCloud& cloud, Vect float maxval = cloud.points[0].x; float minval = cloud.points[0].x; - for (unsigned int i = 0; i < cloud.points.size (); i++) + for (size_t i = 0; i < cloud.points.size (); i++) { if (cloud.points[i].x > maxval) { @@ -85,7 +85,7 @@ pcl::SamplingSurfaceNormal::findXYZMaxMin (const PointCloud& cloud, Vect maxval = cloud.points[0].y; minval = cloud.points[0].y; - for (unsigned int i = 0; i < cloud.points.size (); i++) + for (size_t i = 0; i < cloud.points.size (); i++) { if (cloud.points[i].y > maxval) { @@ -102,7 +102,7 @@ pcl::SamplingSurfaceNormal::findXYZMaxMin (const PointCloud& cloud, Vect maxval = cloud.points[0].z; minval = cloud.points[0].z; - for (unsigned int i = 0; i < cloud.points.size (); i++) + for (size_t i = 0; i < cloud.points.size (); i++) { if (cloud.points[i].z > maxval) { @@ -181,7 +181,7 @@ pcl::SamplingSurfaceNormal::samplePartition ( computeNormal (cloud, normal, curvature); - for (unsigned int i = 0; i < cloud.points.size (); i++) + for (size_t i = 0; i < cloud.points.size (); i++) { // TODO: change to Boost random number generators! const float r = float (std::rand ()) / float (RAND_MAX); @@ -234,8 +234,8 @@ pcl::SamplingSurfaceNormal::computeMeanAndCovarianceMatrix (const pcl::P { // create the buffer on the stack which is much faster than using cloud.points[indices[i]] and centroid as a buffer Eigen::Matrix accu = Eigen::Matrix::Zero (); - unsigned int point_count = 0; - for (unsigned int i = 0; i < cloud.points.size (); i++) + size_t point_count = 0; + for (size_t i = 0; i < cloud.points.size (); i++) { if (!isFinite (cloud[i])) { diff --git a/filters/include/pcl/filters/impl/shadowpoints.hpp b/filters/include/pcl/filters/impl/shadowpoints.hpp index 0d2b5273a9b..65b14141715 100644 --- a/filters/include/pcl/filters/impl/shadowpoints.hpp +++ b/filters/include/pcl/filters/impl/shadowpoints.hpp @@ -51,13 +51,13 @@ pcl::ShadowPoints::applyFilter (PointCloud &output) if (extract_removed_indices_) removed_indices_->resize (input_->points.size ()); - unsigned int cp = 0; - unsigned int ri = 0; - for (unsigned int i = 0; i < input_->points.size (); i++) + size_t cp = 0; + size_t ri = 0; + for (size_t i = 0; i < input_->points.size (); i++) { const NormalT &normal = input_normals_->points[i]; const PointT &pt = input_->points[i]; - float val = fabsf (normal.normal_x * pt.x + normal.normal_y * pt.y + normal.normal_z * pt.z); + const float val = fabsf (normal.normal_x * pt.x + normal.normal_y * pt.y + normal.normal_z * pt.z); if ( (val >= threshold_) ^ negative_) output.points[cp++] = pt; diff --git a/filters/include/pcl/filters/impl/voxel_grid.hpp b/filters/include/pcl/filters/impl/voxel_grid.hpp index 915b973ffbf..27492eb0133 100644 --- a/filters/include/pcl/filters/impl/voxel_grid.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid.hpp @@ -393,7 +393,7 @@ pcl::VoxelGrid::applyFilter (PointCloud &output) } index = 0; - for (unsigned int cp = 0; cp < first_and_last_indices_vector.size (); ++cp) + for (size_t cp = 0; cp < first_and_last_indices_vector.size (); ++cp) { // calculate centroid - sum values from all input points, that have the same idx value in index_vector array unsigned int first_index = first_and_last_indices_vector[cp].first; diff --git a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp index 1aa6fd1aac5..32000ff83a6 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp @@ -386,7 +386,7 @@ pcl::VoxelGridCovariance::getNeighborhoodAtPoint (const PointT& referenc // Check each neighbor to see if it is occupied and contains sufficient points // Slower than radius search because needs to check 26 indices - for (int ni = 0; ni < relative_coordinates.cols (); ni++) + for (Eigen::Index ni = 0; ni < relative_coordinates.cols (); ni++) { Eigen::Vector4i displacement = (Eigen::Vector4i () << relative_coordinates.col (ni), 0).finished (); // Checking if the specified cell is in the grid diff --git a/filters/include/pcl/filters/model_outlier_removal.h b/filters/include/pcl/filters/model_outlier_removal.h index 1c00c5b947e..594d06f8d77 100644 --- a/filters/include/pcl/filters/model_outlier_removal.h +++ b/filters/include/pcl/filters/model_outlier_removal.h @@ -95,7 +95,7 @@ namespace pcl setModelCoefficients (const pcl::ModelCoefficients model_coefficients) { model_coefficients_.resize (model_coefficients.values.size ()); - for (unsigned int i = 0; i < model_coefficients.values.size (); i++) + for (size_t i = 0; i < model_coefficients.values.size (); i++) { model_coefficients_[i] = model_coefficients.values[i]; } @@ -108,7 +108,7 @@ namespace pcl { pcl::ModelCoefficients mc; mc.values.resize (model_coefficients_.size ()); - for (unsigned int i = 0; i < mc.values.size (); i++) + for (size_t i = 0; i < mc.values.size (); i++) mc.values[i] = model_coefficients_[i]; return (mc); } diff --git a/filters/include/pcl/filters/normal_refinement.h b/filters/include/pcl/filters/normal_refinement.h index d041a3a18cd..3cc289e6357 100644 --- a/filters/include/pcl/filters/normal_refinement.h +++ b/filters/include/pcl/filters/normal_refinement.h @@ -102,7 +102,7 @@ namespace pcl float nx = 0.0f; float ny = 0.0f; float nz = 0.0f; - for (unsigned int i = 0; i < k_indices.size (); ++i) { + for (size_t i = 0; i < k_indices.size (); ++i) { // Neighbor const NormalT& pointi = cloud[k_indices[i]]; diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 876eb50f9bf..f3d7f2a1029 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -338,7 +338,7 @@ namespace pcl Eigen::Array4i diff2min = min_b_ - ijk; Eigen::Array4i diff2max = max_b_ - ijk; std::vector neighbors (relative_coordinates.cols()); - for (int ni = 0; ni < relative_coordinates.cols (); ni++) + for (Eigen::Index ni = 0; ni < relative_coordinates.cols (); ni++) { Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished(); // checking if the specified cell is in the grid @@ -668,7 +668,7 @@ namespace pcl Eigen::Array4i diff2min = min_b_ - ijk; Eigen::Array4i diff2max = max_b_ - ijk; std::vector neighbors (relative_coordinates.cols()); - for (int ni = 0; ni < relative_coordinates.cols (); ni++) + for (Eigen::Index ni = 0; ni < relative_coordinates.cols (); ni++) { Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished(); // checking if the specified cell is in the grid diff --git a/geometry/include/pcl/geometry/impl/polygon_operations.hpp b/geometry/include/pcl/geometry/impl/polygon_operations.hpp index d05fd5019ee..28c8f7fa39c 100644 --- a/geometry/include/pcl/geometry/impl/polygon_operations.hpp +++ b/geometry/include/pcl/geometry/impl/polygon_operations.hpp @@ -52,7 +52,7 @@ pcl::approximatePolygon (const PlanarPolygon& polygon, PlanarPolygon::VectorType polygon2D (contour.size ()); - for (unsigned pIdx = 0; pIdx < polygon2D.size (); ++pIdx) + for (size_t pIdx = 0; pIdx < polygon2D.size (); ++pIdx) polygon2D [pIdx].getVector3fMap () = transformation * contour [pIdx].getVector3fMap (); typename pcl::PointCloud::VectorType approx_polygon2D; @@ -62,7 +62,7 @@ pcl::approximatePolygon (const PlanarPolygon& polygon, PlanarPolygon::VectorType &p if (closed) { float max_distance = .0f; - for (unsigned idx = 1; idx < polygon.size (); ++idx) + for (size_t idx = 1; idx < polygon.size (); ++idx) { float distance = (polygon [0].x - polygon [idx].x) * (polygon [0].x - polygon [idx].x) + (polygon [0].y - polygon [idx].y) * (polygon [0].y - polygon [idx].y); @@ -94,7 +94,7 @@ pcl::approximatePolygon2D (const typename pcl::PointCloud::VectorType &p } } - for (unsigned idx = 1; idx < polygon.size (); ++idx) + for (size_t idx = 1; idx < polygon.size (); ++idx) { float distance = (polygon [interval.second].x - polygon [idx].x) * (polygon [interval.second].x - polygon [idx].x) + (polygon [interval.second].y - polygon [idx].y) * (polygon [interval.second].y - polygon [idx].y); @@ -142,7 +142,7 @@ pcl::approximatePolygon2D (const typename pcl::PointCloud::VectorType &p // => 0-crossing if (currentInterval.first > currentInterval.second) { - for (unsigned idx = first_index; idx < polygon.size(); idx++) + for (size_t idx = first_index; idx < polygon.size(); idx++) { float distance = fabsf (line_x * polygon[idx].x + line_y * polygon[idx].y + line_d); if (distance > max_distance) @@ -182,15 +182,15 @@ pcl::approximatePolygon2D (const typename pcl::PointCloud::VectorType &p { std::vector > lines (result.size ()); std::reverse (result.begin (), result.end ()); - for (unsigned rIdx = 0; rIdx < result.size (); ++rIdx) + for (size_t rIdx = 0; rIdx < result.size (); ++rIdx) { - unsigned nIdx = rIdx + 1; + size_t nIdx = rIdx + 1; if (nIdx == result.size ()) nIdx = 0; Eigen::Vector2f centroid = Eigen::Vector2f::Zero (); Eigen::Matrix2f covariance = Eigen::Matrix2f::Zero (); - unsigned pIdx = result[rIdx]; + size_t pIdx = result[rIdx]; unsigned num_points = 0; if (pIdx > result[nIdx]) { @@ -250,9 +250,9 @@ pcl::approximatePolygon2D (const typename pcl::PointCloud::VectorType &p } float threshold2 = threshold * threshold; - for (unsigned rIdx = 0; rIdx < lines.size (); ++rIdx) + for (size_t rIdx = 0; rIdx < lines.size (); ++rIdx) { - unsigned nIdx = rIdx + 1; + size_t nIdx = rIdx + 1; if (nIdx == result.size ()) nIdx = 0; diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index 31e28abf45d..a10f6338c6e 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -571,13 +571,13 @@ namespace pcl if (this->sizeHalfEdges () != other.sizeHalfEdges ()) return (false); if (this->sizeFaces () != other.sizeFaces ()) return (false); - for (unsigned int i=0; isizeVertices (); ++i) + for (size_t i=0; isizeVertices (); ++i) { if (this->getOutgoingHalfEdgeIndex (VertexIndex (i)) != other.getOutgoingHalfEdgeIndex (VertexIndex (i))) return (false); } - for (unsigned int i=0; isizeHalfEdges (); ++i) + for (size_t i=0; isizeHalfEdges (); ++i) { if (this->getTerminatingVertexIndex (HalfEdgeIndex (i)) != other.getTerminatingVertexIndex (HalfEdgeIndex (i))) return (false); @@ -592,7 +592,7 @@ namespace pcl other.getFaceIndex (HalfEdgeIndex (i))) return (false); } - for (unsigned int i=0; isizeFaces (); ++i) + for (size_t i=0; isizeFaces (); ++i) { if (this->getInnerHalfEdgeIndex (FaceIndex (i)) != other.getInnerHalfEdgeIndex (FaceIndex (i))) return (false); @@ -1953,7 +1953,7 @@ namespace pcl bool isManifold (boost::false_type /*is_manifold*/) const { - for (unsigned int i=0; isizeVertices (); ++i) + for (size_t i=0; isizeVertices (); ++i) { if (!this->isManifold (VertexIndex (i))) return (false); } diff --git a/gpu/kinfu_large_scale/src/cyclical_buffer.cpp b/gpu/kinfu_large_scale/src/cyclical_buffer.cpp index 3b957245cce..c2ae10b40ea 100644 --- a/gpu/kinfu_large_scale/src/cyclical_buffer.cpp +++ b/gpu/kinfu_large_scale/src/cyclical_buffer.cpp @@ -111,7 +111,7 @@ pcl::gpu::kinfuLS::CyclicalBuffer::performShift (const TsdfVolume::Ptr volume, c std::vector > intensities_vector; intensities.download (intensities_vector); current_slice_intensities->points.resize (current_slice_xyz->points.size ()); - for(int i = 0 ; i < current_slice_intensities->points.size () ; ++i) + for(size_t i = 0 ; i < current_slice_intensities->points.size () ; ++i) current_slice_intensities->points[i].intensity = intensities_vector[i]; current_slice_intensities->width = (int) current_slice_intensities->points.size (); diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index a7978f0371f..ddc97d16098 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -277,7 +277,7 @@ void showCameras (pcl::texture_mapping::CameraVector cams, pcl::PointCloud::Camera cam = cams[i]; @@ -351,7 +351,7 @@ void showCameras (pcl::texture_mapping::CameraVector cams, pcl::PointCloud::max (),'\n'); } @@ -464,7 +464,7 @@ main (int argc, char** argv) // Create materials for each texture (and one extra for occluded faces) mesh.tex_materials.resize (my_cams.size () + 1); - for(int i = 0 ; i <= my_cams.size() ; ++i) + for(size_t i = 0 ; i <= my_cams.size() ; ++i) { pcl::TexMaterial mesh_material; mesh_material.tex_Ka.r = 0.2f; @@ -503,7 +503,7 @@ main (int argc, char** argv) PCL_INFO ("Sorting faces by cameras done.\n"); - for(int i = 0 ; i <= my_cams.size() ; ++i) + for(size_t i = 0 ; i <= my_cams.size() ; ++i) { PCL_INFO ("\tSub mesh %d contains %d faces and %d UV coordinates.\n", i, mesh.tex_polygons[i].size (), mesh.tex_coordinates[i].size ()); } diff --git a/gpu/people/src/face_detector.cpp b/gpu/people/src/face_detector.cpp index 8ca4c4f7e85..b05f4c572e9 100644 --- a/gpu/people/src/face_detector.cpp +++ b/gpu/people/src/face_detector.cpp @@ -327,7 +327,7 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string //merge root and leaf nodes in one classifiers array, leaf nodes are sorted behind the root nodes Ncv32u offset_root = haarClassifierNodes.size(); - for (Ncv32u i=0; i& NCV_SKIP_COND_BEGIN - for(int i=0; i& PCL_ASSERT_CUDA_RETURN(cudaStreamSynchronize(0), NCV_CUDA_ERROR); // Copy result back into output cloud - for(int i=0; i::Con } // Fill in the probabilities - for(int plane = 0; plane < inlier_indices.size(); plane++) // iterate over all found planes + for(size_t plane = 0; plane < inlier_indices.size(); plane++) // iterate over all found planes { - for(int idx = 0; idx < inlier_indices[plane].indices.size(); idx++) // iterate over all the indices in that plane + for(size_t idx = 0; idx < inlier_indices[plane].indices.size(); idx++) // iterate over all the indices in that plane { P_l_host_.points[inlier_indices[plane].indices[idx]].probs[pcl::gpu::people::Background] = 1.f; // set background at max } @@ -140,7 +140,7 @@ pcl::gpu::people::OrganizedPlaneDetector::allocate_buffers(int rows, int cols) void pcl::gpu::people::OrganizedPlaneDetector::emptyHostLabelProbability(HostLabelProbability& histogram) { - for(int hist = 0; hist < histogram.points.size(); hist++) + for(size_t hist = 0; hist < histogram.points.size(); hist++) { for(int label = 0; label < pcl::gpu::people::NUM_LABELS; label++) { @@ -158,7 +158,7 @@ pcl::gpu::people::OrganizedPlaneDetector::copyHostLabelProbability(HostLabelProb PCL_ERROR("[pcl::gpu::people::OrganizedPlaneDetector::copyHostLabelProbability] : (E) : Sizes don't match\n"); return -1; } - for(int hist = 0; hist < src.points.size(); hist++) + for(size_t hist = 0; hist < src.points.size(); hist++) { for(int label = 0; label < pcl::gpu::people::NUM_LABELS; label++) { @@ -177,7 +177,7 @@ pcl::gpu::people::OrganizedPlaneDetector::copyAndClearHostLabelProbability(HostL PCL_ERROR("[pcl::gpu::people::OrganizedPlaneDetector::copyHostLabelProbability] : (E) : Sizes don't match\n"); return -1; } - for(int hist = 0; hist < src.points.size(); hist++) + for(size_t hist = 0; hist < src.points.size(); hist++) { for(int label = 0; label < pcl::gpu::people::NUM_LABELS; label++) { diff --git a/gpu/people/tools/people_app.cpp b/gpu/people/tools/people_app.cpp index 7829106f449..11add960c12 100644 --- a/gpu/people/tools/people_app.cpp +++ b/gpu/people/tools/people_app.cpp @@ -256,7 +256,7 @@ class PeoplePCDApp rgba_host_.points.resize(w * h); rgba_host_.width = w; rgba_host_.height = h; - for(int i = 0; i < rgba_host_.size(); ++i) + for(size_t i = 0; i < rgba_host_.size(); ++i) { const unsigned char *pixel = &rgb_host_[i * 3]; RGB& rgba = rgba_host_.points[i]; diff --git a/io/include/pcl/compression/impl/entropy_range_coder.hpp b/io/include/pcl/compression/impl/entropy_range_coder.hpp index 41cb9146a3e..88bbafa856c 100644 --- a/io/include/pcl/compression/impl/entropy_range_coder.hpp +++ b/io/include/pcl/compression/impl/entropy_range_coder.hpp @@ -273,7 +273,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& input frequencyTableSize++; // convert to cumulative frequency table - for (unsigned int f = 1; f < frequencyTableSize; f++) + for (uint64_t f = 1; f < frequencyTableSize; f++) { cFreqTable_[f] = cFreqTable_[f - 1] + cFreqTable_[f]; if (cFreqTable_[f] <= cFreqTable_[f - 1]) @@ -283,7 +283,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& input // rescale if numerical limits are reached while (cFreqTable_[static_cast (frequencyTableSize - 1)] >= maxRange) { - for (unsigned int f = 1; f < cFreqTable_.size (); f++) + for (size_t f = 1; f < cFreqTable_.size (); f++) { cFreqTable_[f] /= 2; ; @@ -303,7 +303,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& input unsigned long streamByteCount = sizeof(frequencyTableSize) + sizeof(frequencyTableByteSize); // write cumulative frequency table to output stream - for (unsigned int f = 1; f < frequencyTableSize; f++) + for (uint64_t f = 1; f < frequencyTableSize; f++) { outputByteStream_arg.write (reinterpret_cast (&cFreqTable_[f]), frequencyTableByteSize); streamByteCount += frequencyTableByteSize; @@ -364,7 +364,7 @@ pcl::StaticRangeCoder::decodeStreamToIntVector (std::istream& inputByteStream_ar unsigned char frequencyTableByteSize; unsigned int outputBufPos = 0; - unsigned long output_size = static_cast (outputIntVector_arg.size ()); + size_t output_size = outputIntVector_arg.size (); // read size of cumulative frequency table from stream inputByteStream_arg.read (reinterpret_cast (&frequencyTableSize), sizeof(frequencyTableSize)); @@ -382,7 +382,7 @@ pcl::StaticRangeCoder::decodeStreamToIntVector (std::istream& inputByteStream_ar memset (&cFreqTable_[0], 0, sizeof(uint64_t) * static_cast (frequencyTableSize)); // read cumulative frequency table - for (unsigned int f = 1; f < frequencyTableSize; f++) + for (uint64_t f = 1; f < frequencyTableSize; f++) { inputByteStream_arg.read (reinterpret_cast (&cFreqTable_[f]), frequencyTableByteSize); streamByteCount += frequencyTableByteSize; @@ -403,7 +403,7 @@ pcl::StaticRangeCoder::decodeStreamToIntVector (std::istream& inputByteStream_ar } // decoding - for (unsigned int i = 0; i < output_size; i++) + for (size_t i = 0; i < output_size; i++) { uint64_t count = (code - low) / (range /= cFreqTable_[static_cast (frequencyTableSize - 1)]); diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index 4b271773870..d8bfec51ddf 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -560,10 +560,10 @@ pcl::io::OpenNI2Grabber::convertToXYZPointCloud (const DepthImage::Ptr& depth_im depth_map = depth_resize_buffer_.data(); } - int depth_idx = 0; - for (int v = 0; v < depth_height_; ++v) + unsigned depth_idx = 0; + for (unsigned v = 0; v < depth_height_; ++v) { - for (int u = 0; u < depth_width_; ++u, ++depth_idx) + for (unsigned u = 0; u < depth_width_; ++u, ++depth_idx) { pcl::PointXYZ& pt = cloud->points[depth_idx]; // Check for invalid measurements @@ -662,11 +662,11 @@ pcl::io::OpenNI2Grabber::convertToXYZRGBPointCloud (const Image::Ptr &image, con unsigned step = cloud->width / depth_width_; unsigned skip = cloud->width - (depth_width_ * step); - int value_idx = 0; - int point_idx = 0; - for (int v = 0; v < depth_height_; ++v, point_idx += skip) + unsigned value_idx = 0; + unsigned point_idx = 0; + for (unsigned v = 0; v < depth_height_; ++v, point_idx += skip) { - for (int u = 0; u < depth_width_; ++u, ++value_idx, point_idx += step) + for (unsigned u = 0; u < depth_width_; ++u, ++value_idx, point_idx += step) { PointT& pt = cloud->points[point_idx]; /// @todo Different values for these cases @@ -773,12 +773,12 @@ pcl::io::OpenNI2Grabber::convertToXYZIPointCloud (const IRImage::Ptr &ir_image, } - int depth_idx = 0; + size_t depth_idx = 0; float bad_point = std::numeric_limits::quiet_NaN (); - for (int v = 0; v < depth_height_; ++v) + for (unsigned v = 0; v < depth_height_; ++v) { - for (int u = 0; u < depth_width_; ++u, ++depth_idx) + for (unsigned u = 0; u < depth_width_; ++u, ++depth_idx) { pcl::PointXYZI& pt = cloud->points[depth_idx]; /// @todo Different values for these cases diff --git a/io/src/openni_camera/openni_driver.cpp b/io/src/openni_camera/openni_driver.cpp index 4463c9fc971..82201b51380 100644 --- a/io/src/openni_camera/openni_driver.cpp +++ b/io/src/openni_camera/openni_driver.cpp @@ -166,7 +166,7 @@ openni_wrapper::OpenNIDriver::updateDeviceList () #ifndef _WIN32 // add context object for each found device - for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) + for (size_t deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) { // register bus@address to the corresponding context object unsigned short vendor_id; @@ -181,7 +181,7 @@ openni_wrapper::OpenNIDriver::updateDeviceList () getDeviceInfos (); #endif // build serial number -> device index map - for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) + for (size_t deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) { std::string serial_number = getSerialNumber (deviceIdx); if (!serial_number.empty ()) @@ -190,7 +190,7 @@ openni_wrapper::OpenNIDriver::updateDeviceList () // redundant, but needed for Windows right now and also for Xtion - for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) + for (size_t deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) { unsigned short product_id; unsigned short vendor_id; diff --git a/io/src/vtk_lib_io.cpp b/io/src/vtk_lib_io.cpp index 91d76f48626..23691df3ca4 100644 --- a/io/src/vtk_lib_io.cpp +++ b/io/src/vtk_lib_io.cpp @@ -357,7 +357,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer& poly_data, pcl::PolygonMe while (mesh_polygons->GetNextCell (nr_cell_points, cell_points)) { mesh.polygons[id_poly].vertices.resize (nr_cell_points); - for (int i = 0; i < nr_cell_points; ++i) + for (vtkIdType i = 0; i < nr_cell_points; ++i) mesh.polygons[id_poly].vertices[i] = static_cast (cell_points[i]); ++id_poly; } diff --git a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp index d548deb84cf..9478337cdb5 100644 --- a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp @@ -437,7 +437,7 @@ template void pcl::HarrisKeypoint3D::responseCurvature (PointCloudOut &output) const { PointOutT point; - for (unsigned idx = 0; idx < input_->points.size(); ++idx) + for (size_t idx = 0; idx < input_->points.size(); ++idx) { point.x = input_->points[idx].x; point.y = input_->points[idx].y; diff --git a/keypoints/include/pcl/keypoints/impl/harris_6d.hpp b/keypoints/include/pcl/keypoints/impl/harris_6d.hpp index 1c565c4fbb3..65df7efc7d6 100644 --- a/keypoints/include/pcl/keypoints/impl/harris_6d.hpp +++ b/keypoints/include/pcl/keypoints/impl/harris_6d.hpp @@ -187,7 +187,7 @@ pcl::HarrisKeypoint6D::detectKeypoints (PointCloud #ifdef _OPENMP #pragma omp parallel for num_threads(threads_) default (shared) #endif - for (unsigned idx = 0; idx < intensity_gradients_->size (); ++idx) + for (size_t idx = 0; idx < intensity_gradients_->size (); ++idx) { float len = intensity_gradients_->points [idx].gradient_x * intensity_gradients_->points [idx].gradient_x + intensity_gradients_->points [idx].gradient_y * intensity_gradients_->points [idx].gradient_y + diff --git a/keypoints/include/pcl/keypoints/impl/iss_3d.hpp b/keypoints/include/pcl/keypoints/impl/iss_3d.hpp index 444f1524fe4..4b689f26fc3 100644 --- a/keypoints/include/pcl/keypoints/impl/iss_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/iss_3d.hpp @@ -381,7 +381,7 @@ pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut omp_mem[tid][2] = e3c; } - for (int d = 0; d < omp_mem[tid].size (); d++) + for (Eigen::Index d = 0; d < omp_mem[tid].size (); d++) prg_mem[index][d] = omp_mem[tid][d]; } diff --git a/ml/src/densecrf.cpp b/ml/src/densecrf.cpp index 938e724c496..4a852f509a0 100644 --- a/ml/src/densecrf.cpp +++ b/ml/src/densecrf.cpp @@ -294,7 +294,7 @@ pcl::DenseCrf::runInference (float relax) next_[i] = -unary_[i]; // Add up all pairwise potentials - for( unsigned int i = 0; i < pairwise_potential_.size(); i++ ) + for( size_t i = 0; i < pairwise_potential_.size(); i++ ) pairwise_potential_[i]->compute( next_, current_, tmp_, M_ ); // Exponentiate and normalize diff --git a/people/apps/main_ground_based_people_detection.cpp b/people/apps/main_ground_based_people_detection.cpp index b44d3197cd3..e95bcea316a 100644 --- a/people/apps/main_ground_based_people_detection.cpp +++ b/people/apps/main_ground_based_people_detection.cpp @@ -173,7 +173,7 @@ int main (int argc, char** argv) Eigen::VectorXf ground_coeffs; ground_coeffs.resize(4); std::vector clicked_points_indices; - for (unsigned int i = 0; i < clicked_points_3d->points.size(); i++) + for (size_t i = 0; i < clicked_points_3d->points.size(); i++) clicked_points_indices.push_back(i); pcl::SampleConsensusModelPlane model_plane(clicked_points_3d); model_plane.computeModelCoefficients(clicked_points_indices,ground_coeffs); diff --git a/people/include/pcl/people/impl/head_based_subcluster.hpp b/people/include/pcl/people/impl/head_based_subcluster.hpp index 5f88be2a107..aee0b5df478 100644 --- a/people/include/pcl/people/impl/head_based_subcluster.hpp +++ b/people/include/pcl/people/impl/head_based_subcluster.hpp @@ -141,12 +141,12 @@ pcl::people::HeadBasedSubclustering::mergeClustersCloseInFloorCoordinate connected_clusters.resize(input_clusters.size()); std::vector used_clusters; // 0 in correspondence of clusters remained to process, 1 for already used clusters used_clusters.resize(input_clusters.size()); - for(unsigned int i = 0; i < input_clusters.size(); i++) // for every cluster + for(size_t i = 0; i < input_clusters.size(); i++) // for every cluster { Eigen::Vector3f theoretical_center = input_clusters[i].getTCenter(); float t = theoretical_center.dot(head_ground_coeffs) / normalize_factor; // height from the ground Eigen::Vector3f current_cluster_center_projection = theoretical_center - head_ground_coeffs * t; // projection of the point on the groundplane - for(unsigned int j = i+1; j < input_clusters.size(); j++) // for every remaining cluster + for(size_t j = i+1; j < input_clusters.size(); j++) // for every remaining cluster { theoretical_center = input_clusters[j].getTCenter(); float t = theoretical_center.dot(head_ground_coeffs) / normalize_factor; // height from the ground @@ -158,7 +158,7 @@ pcl::people::HeadBasedSubclustering::mergeClustersCloseInFloorCoordinate } } - for(unsigned int i = 0; i < connected_clusters.size(); i++) // for every cluster + for(size_t i = 0; i < connected_clusters.size(); i++) // for every cluster { if (!used_clusters[i]) // if this cluster has not been used yet { @@ -172,7 +172,7 @@ pcl::people::HeadBasedSubclustering::mergeClustersCloseInFloorCoordinate // Copy cluster points into new cluster: pcl::PointIndices point_indices; point_indices = input_clusters[i].getIndices(); - for(unsigned int j = 0; j < connected_clusters[i].size(); j++) + for(size_t j = 0; j < connected_clusters[i].size(); j++) { if (!used_clusters[connected_clusters[i][j]]) // if this cluster has not been used yet { @@ -280,7 +280,7 @@ pcl::people::HeadBasedSubclustering::subcluster (std::vector > new_clusters; - for(unsigned int i = 0; i < clusters.size(); i++) // for every cluster + for(size_t i = 0; i < clusters.size(); i++) // for every cluster { if (clusters[i].getHeight() <= max_height_) new_clusters.push_back(clusters[i]); diff --git a/people/include/pcl/people/impl/person_classifier.hpp b/people/include/pcl/people/impl/person_classifier.hpp index eeadc77416e..65e1e9692ea 100644 --- a/people/include/pcl/people/impl/person_classifier.hpp +++ b/people/include/pcl/people/impl/person_classifier.hpp @@ -260,7 +260,7 @@ pcl::people::PersonClassifier::evaluate (float height_person, // Calculate confidence value by dot product: confidence = 0.0; - for(unsigned int i = 0; i < SVM_weights_.size(); i++) + for(size_t i = 0; i < SVM_weights_.size(); i++) { confidence += SVM_weights_[i] * descriptor[i]; } diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index 23c5da9b746..a58f27998ea 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -917,7 +917,7 @@ pcl::ism::ImplicitShapeModelEstimation::clusterDes { Eigen::MatrixXf points_to_cluster (histograms.size (), FeatureSize); - for (unsigned int i_feature = 0; i_feature < histograms.size (); i_feature++) + for (size_t i_feature = 0; i_feature < histograms.size (); i_feature++) for (int i_dim = 0; i_dim < FeatureSize; i_dim++) points_to_cluster (i_feature, i_dim) = histograms[i_feature].histogram[i_dim]; @@ -941,7 +941,7 @@ pcl::ism::ImplicitShapeModelEstimation::calculateS if (training_sigmas_.size () != 0) { sigmas.resize (training_sigmas_.size (), 0.0f); - for (unsigned int i_sigma = 0; i_sigma < training_sigmas_.size (); i_sigma++) + for (size_t i_sigma = 0; i_sigma < training_sigmas_.size (); i_sigma++) sigmas[i_sigma] = training_sigmas_[i_sigma]; return; } @@ -1311,7 +1311,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeKMe for (int i_dim = 0; i_dim < feature_dimension; i_dim++) box[i_dim] = Eigen::Vector2f (points_to_cluster (0, i_dim), points_to_cluster (0, i_dim)); - for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + for (size_t i_point = 0; i_point < number_of_points; i_point++) for (int i_dim = 0; i_dim < feature_dimension; i_dim++) { float v = points_to_cluster (i_point, i_dim); @@ -1349,7 +1349,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeKMe centers.setZero (); for (int i_cluster = 0; i_cluster < number_of_clusters; i_cluster++) counters[i_cluster] = 0; - for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + for (size_t i_point = 0; i_point < number_of_points; i_point++) { int i_label = labels (i_point, 0); for (int i_dim = 0; i_dim < feature_dimension; i_dim++) @@ -1387,7 +1387,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeKMe } } compactness = 0.0f; - for (unsigned int i_point = 0; i_point < number_of_points; i_point++) + for (size_t i_point = 0; i_point < number_of_points; i_point++) { Eigen::VectorXf sample (feature_dimension); sample = points_to_cluster.row (i_point); @@ -1494,7 +1494,7 @@ pcl::ism::ImplicitShapeModelEstimation::generateCe } for (int i_cluster = 0; i_cluster < number_of_clusters; i_cluster++) - for (unsigned int i_dim = 0; i_dim < dimension; i_dim++) + for (size_t i_dim = 0; i_dim < dimension; i_dim++) out_centers (i_cluster, i_dim) = data (centers[i_cluster], i_dim); } @@ -1506,7 +1506,7 @@ pcl::ism::ImplicitShapeModelEstimation::generateRa size_t dimension = boxes.size (); float margin = 1.0f / static_cast (dimension); - for (unsigned int i_dim = 0; i_dim < dimension; i_dim++) + for (size_t i_dim = 0; i_dim < dimension; i_dim++) { unsigned int random_integer = rand () - 1; float random_float = static_cast (random_integer) / static_cast (std::numeric_limits::max ()); @@ -1520,7 +1520,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeDis { size_t dimension = vec_1.rows () > 1 ? vec_1.rows () : vec_1.cols (); float distance = 0.0f; - for(unsigned int i_dim = 0; i_dim < dimension; i_dim++) + for(size_t i_dim = 0; i_dim < dimension; i_dim++) { float diff = vec_1 (i_dim) - vec_2 (i_dim); distance += diff * diff; diff --git a/registration/include/pcl/registration/impl/ndt.hpp b/registration/include/pcl/registration/impl/ndt.hpp index 0ef10504b3e..7210c865933 100644 --- a/registration/include/pcl/registration/impl/ndt.hpp +++ b/registration/include/pcl/registration/impl/ndt.hpp @@ -385,7 +385,7 @@ pcl::NormalDistributionsTransform::updateDerivatives ( if (compute_hessian) { - for (int j = 0; j < hessian.cols (); j++) + for (Eigen::Index j = 0; j < hessian.cols (); j++) { // Update hessian, Equation 6.13 [Magnusson 2009] hessian (i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot (cov_dxd_pi) * x_trans.dot (c_inv * point_gradient_.col (j)) + @@ -470,7 +470,7 @@ pcl::NormalDistributionsTransform::updateHessian (Eige // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009] cov_dxd_pi = c_inv * point_gradient_.col (i); - for (int j = 0; j < hessian.cols (); j++) + for (Eigen::Index j = 0; j < hessian.cols (); j++) { // Update hessian, Equation 6.13 [Magnusson 2009] hessian (i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot (cov_dxd_pi) * x_trans.dot (c_inv * point_gradient_.col (j)) + diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp index 1f255af0639..542e3d1d740 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp @@ -278,7 +278,7 @@ pcl::SampleConsensusModelCircle3D::optimizeModelCoefficients ( Eigen::LevenbergMarquardt, double> lm (num_diff); Eigen::VectorXd coeff; int info = lm.minimize (coeff); - for (int i = 0; i < coeff.size (); ++i) + for (Eigen::Index i = 0; i < coeff.size (); ++i) optimized_coefficients[i] = static_cast (coeff[i]); // Compute the L2 norm of the residuals diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model.h b/sample_consensus/include/pcl/sample_consensus/sac_model.h index 7173d1d84bf..65add111c53 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model.h @@ -455,7 +455,7 @@ namespace pcl { size_t sample_size = sample.size (); size_t index_size = shuffled_indices_.size (); - for (unsigned int i = 0; i < sample_size; ++i) + for (size_t i = 0; i < sample_size; ++i) // The 1/(RAND_MAX+1.0) trick is when the random numbers are not uniformly distributed and for small modulo // elements, that does not matter (and nowadays, random number generators are good) //std::swap (shuffled_indices_[i], shuffled_indices_[i + (rand () % (index_size - i))]); @@ -490,14 +490,14 @@ namespace pcl if (indices.size () < sample_size - 1) { // radius search failed, make an invalid model - for(unsigned int i = 1; i < sample_size; ++i) + for(size_t i = 1; i < sample_size; ++i) shuffled_indices_[i] = shuffled_indices_[0]; } else { - for (unsigned int i = 0; i < sample_size-1; ++i) + for (size_t i = 0; i < sample_size-1; ++i) std::swap (indices[i], indices[i + (rnd () % (indices.size () - i))]); - for (unsigned int i = 1; i < sample_size; ++i) + for (size_t i = 1; i < sample_size; ++i) shuffled_indices_[i] = indices[i-1]; } diff --git a/search/include/pcl/search/impl/brute_force.hpp b/search/include/pcl/search/impl/brute_force.hpp index 6563d18200f..357b344791a 100644 --- a/search/include/pcl/search/impl/brute_force.hpp +++ b/search/include/pcl/search/impl/brute_force.hpp @@ -250,7 +250,7 @@ pcl::search::BruteForce::denseRadiusSearch ( } else { - for (unsigned index = 0; index < input_->size (); ++index) + for (size_t index = 0; index < input_->size (); ++index) { distance = getDistSqr (input_->points[index], point); if (distance <= radius) @@ -309,7 +309,7 @@ pcl::search::BruteForce::sparseRadiusSearch ( } else { - for (unsigned index = 0; index < input_->size (); ++index) + for (size_t index = 0; index < input_->size (); ++index) { if (!std::isfinite (input_->points[index].x)) continue; diff --git a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h index e800d44e74c..45693eb0258 100644 --- a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h @@ -252,7 +252,7 @@ namespace pcl setExcludeLabels (const std::vector& exclude_labels) { exclude_labels_ = boost::make_shared > (); - for (uint32_t i = 0; i < exclude_labels.size (); ++i) + for (size_t i = 0; i < exclude_labels.size (); ++i) if (exclude_labels[i]) exclude_labels_->insert (i); } diff --git a/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp index 9b9fe4c4e3b..bdfc2b2190a 100644 --- a/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp @@ -125,7 +125,7 @@ pcl::OrganizedConnectedComponentSegmentation::segment (pcl::Poi labels.points.resize (input_->points.size (), invalid_pt); labels.width = input_->width; labels.height = input_->height; - unsigned int clust_id = 0; + size_t clust_id = 0; //First pixel if (std::isfinite (input_->points[0].x)) @@ -205,8 +205,8 @@ pcl::OrganizedConnectedComponentSegmentation::segment (pcl::Poi } std::vector map (clust_id); - unsigned max_id = 0; - for (unsigned runIdx = 0; runIdx < run_ids.size (); ++runIdx) + size_t max_id = 0; + for (size_t runIdx = 0; runIdx < run_ids.size (); ++runIdx) { // if it is its own root -> new region if (run_ids[runIdx] == runIdx) @@ -216,7 +216,7 @@ pcl::OrganizedConnectedComponentSegmentation::segment (pcl::Poi } label_indices.resize (max_id + 1); - 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) { diff --git a/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp index bfe32493879..11bb0b2804a 100644 --- a/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp @@ -111,7 +111,7 @@ pcl::OrganizedMultiPlaneSegmentation::segment (std::ve // Calculate range part of planes' hessian normal form std::vector plane_d (input_->points.size ()); - for (unsigned int i = 0; i < input_->size (); ++i) + for (size_t i = 0; i < input_->size (); ++i) plane_d[i] = input_->points[i].getVector3fMap ().dot (normals_->points[i].getNormalVector3fMap ()); // Make a comparator @@ -204,7 +204,7 @@ pcl::OrganizedMultiPlaneSegmentation::segment (std::ve boundary_cloud.resize (0); pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (inlier_indices[i].indices[0], labels, boundary_indices[i]); boundary_cloud.points.resize (boundary_indices[i].indices.size ()); - for (unsigned j = 0; j < boundary_indices[i].indices.size (); j++) + for (size_t j = 0; j < boundary_indices[i].indices.size (); j++) boundary_cloud.points[j] = input_->points[boundary_indices[i].indices[j]]; Eigen::Vector3f centroid = Eigen::Vector3f (centroids[i][0],centroids[i][1],centroids[i][2]); @@ -243,7 +243,7 @@ pcl::OrganizedMultiPlaneSegmentation::segmentAndRefine int max_inlier_idx = static_cast (inlier_indices[i].indices.size ()) - 1; pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (inlier_indices[i].indices[max_inlier_idx], labels, boundary_indices[i]); boundary_cloud.points.resize (boundary_indices[i].indices.size ()); - for (unsigned j = 0; j < boundary_indices[i].indices.size (); j++) + for (size_t j = 0; j < boundary_indices[i].indices.size (); j++) boundary_cloud.points[j] = input_->points[boundary_indices[i].indices[j]]; Eigen::Vector3f centroid = Eigen::Vector3f (centroids[i][0],centroids[i][1],centroids[i][2]); @@ -287,7 +287,7 @@ pcl::OrganizedMultiPlaneSegmentation::segmentAndRefine int max_inlier_idx = static_cast (inlier_indices[i].indices.size ()) - 1; pcl::OrganizedConnectedComponentSegmentation::findLabeledRegionBoundary (inlier_indices[i].indices[max_inlier_idx], labels, boundary_indices[i]); boundary_cloud.points.resize (boundary_indices[i].indices.size ()); - for (unsigned j = 0; j < boundary_indices[i].indices.size (); j++) + for (size_t j = 0; j < boundary_indices[i].indices.size (); j++) boundary_cloud.points[j] = input_->points[boundary_indices[i].indices[j]]; Eigen::Vector3f centroid = Eigen::Vector3f (centroids[i][0],centroids[i][1],centroids[i][2]); diff --git a/segmentation/include/pcl/segmentation/impl/random_walker.hpp b/segmentation/include/pcl/segmentation/impl/random_walker.hpp index 9765b3a6fca..639ed4efe28 100644 --- a/segmentation/include/pcl/segmentation/impl/random_walker.hpp +++ b/segmentation/include/pcl/segmentation/impl/random_walker.hpp @@ -193,7 +193,7 @@ namespace pcl Eigen::SimplicialCholesky cg; cg.compute (L); bool succeeded = true; - for (int i = 0; i < B.cols (); ++i) + for (Eigen::Index i = 0; i < B.cols (); ++i) { Vector b = B.col (i); X.col (i) = cg.solve (b); @@ -210,7 +210,7 @@ namespace pcl { using namespace boost; if (X.cols ()) - for (int i = 0; i < X.rows (); ++i) + for (Eigen::Index i = 0; i < X.rows (); ++i) { size_t max_column; X.row (i).maxCoeff (&max_column); @@ -226,7 +226,7 @@ namespace pcl using namespace boost; potentials = Matrix::Zero (num_vertices (g_), colors_.size ()); // Copy over rows from X - for (int i = 0; i < X.rows (); ++i) + for (Eigen::Index i = 0; i < X.rows (); ++i) potentials.row (L_vertex_bimap.left.at (i)).head (X.cols ()) = X.row (i); // In rows that correspond to seeds put ones in proper columns for (size_t i = 0; i < seeds_.size (); ++i) @@ -237,7 +237,7 @@ namespace pcl } // Fill in a map that associates colors with columns in potentials matrix color_to_column_map.clear (); - for (int i = 0; i < potentials.cols (); ++i) + for (Eigen::Index i = 0; i < potentials.cols (); ++i) color_to_column_map[B_color_bimap.left.at (i)] = i; } diff --git a/surface/include/pcl/surface/impl/gp3.hpp b/surface/include/pcl/surface/impl/gp3.hpp index af072ce9f73..f9c9de7267d 100644 --- a/surface/include/pcl/surface/impl/gp3.hpp +++ b/surface/include/pcl/surface/impl/gp3.hpp @@ -276,7 +276,7 @@ pcl::GreedyProjectionTriangulation::reconstructPolygons (std::vector

size (); temp++) + for (size_t temp = 0; temp < indices_->size (); temp++) { if (state_[temp] == FREE) { diff --git a/surface/include/pcl/surface/impl/mls.hpp b/surface/include/pcl/surface/impl/mls.hpp index 90fe24854d2..70303173e03 100644 --- a/surface/include/pcl/surface/impl/mls.hpp +++ b/surface/include/pcl/surface/impl/mls.hpp @@ -148,7 +148,7 @@ pcl::MovingLeastSquares::process (PointCloudOut &output) normals_->height = 1; normals_->width = static_cast (normals_->size ()); - for (unsigned int i = 0; i < output.size (); ++i) + for (size_t i = 0; i < output.size (); ++i) { typedef typename pcl::traits::fieldList::type FieldList; pcl::for_each_type (SetIfFieldExists (output.points[i], "normal_x", normals_->points[i].normal_x)); @@ -846,7 +846,7 @@ pcl::MovingLeastSquares::MLSVoxelGrid::MLSVoxelGrid (PointC const double max_size = (std::max) ((std::max)(bounding_box_size.x (), bounding_box_size.y ()), bounding_box_size.z ()); // Put initial cloud in voxel grid data_size_ = static_cast (1.5 * max_size / voxel_size_); - for (unsigned int i = 0; i < indices->size (); ++i) + for (size_t i = 0; i < indices->size (); ++i) if (std::isfinite (cloud->points[(*indices)[i]].x)) { Eigen::Vector3i pos; diff --git a/surface/include/pcl/surface/impl/organized_fast_mesh.hpp b/surface/include/pcl/surface/impl/organized_fast_mesh.hpp index 074b232b78c..a600b8a561d 100644 --- a/surface/include/pcl/surface/impl/organized_fast_mesh.hpp +++ b/surface/include/pcl/surface/impl/organized_fast_mesh.hpp @@ -59,7 +59,7 @@ pcl::OrganizedFastMesh::performReconstruction (pcl::PolygonMesh &outpu // (running over complete image since some rows and columns are left out // depending on triangle_pixel_size) // avoid to do that here (only needed for ASCII mesh file output, e.g., in vtk files - for (unsigned int i = 0; i < input_->points.size (); ++i) + for (size_t i = 0; i < input_->points.size (); ++i) if (!isFinite (input_->points[i])) resetPointData (i, output, 0.0f, x_idx, y_idx, z_idx); } diff --git a/surface/src/on_nurbs/closing_boundary.cpp b/surface/src/on_nurbs/closing_boundary.cpp index 91df8cedbe6..0a8aafee032 100644 --- a/surface/src/on_nurbs/closing_boundary.cpp +++ b/surface/src/on_nurbs/closing_boundary.cpp @@ -330,11 +330,11 @@ void ClosingBoundary::optimizeBoundary (std::vector &nurbs_list, std::vector &data_list, Parameter param) { - for (unsigned n1 = 0; n1 < nurbs_list.size (); n1++) + for (size_t n1 = 0; n1 < nurbs_list.size (); n1++) data_list[n1].clear_boundary (); // for each nurbs - for (unsigned n1 = 0; n1 < nurbs_list.size (); n1++) + for (size_t n1 = 0; n1 < nurbs_list.size (); n1++) { // for (unsigned n1 = 0; n1 < 1; n1++) { ON_NurbsSurface *nurbs1 = &nurbs_list[n1]; @@ -345,12 +345,12 @@ ClosingBoundary::optimizeBoundary (std::vector &nurbs_list, std sampleFromBoundary (nurbs1, boundary1, params1, param.samples); // for each other nurbs - for (unsigned n2 = (n1 + 1); n2 < nurbs_list.size (); n2++) + for (size_t n2 = (n1 + 1); n2 < nurbs_list.size (); n2++) { ON_NurbsSurface *nurbs2 = &nurbs_list[n2]; // for all points in the point list - for (unsigned i = 0; i < boundary1.size (); i++) + for (size_t i = 0; i < boundary1.size (); i++) { double error; Eigen::Vector3d p, tu, tv; @@ -392,12 +392,12 @@ ClosingBoundary::optimizeBoundary (std::vector &nurbs_list, std FittingSurface::Parameter paramFP (1.0, param.smoothness, 0.0, 1.0, param.smoothness, 0.0); std::vector wBnd, wInt; - for (unsigned i = 0; i < data_list[n1].boundary.size (); i++) + for (size_t i = 0; i < data_list[n1].boundary.size (); i++) data_list[n1].boundary_weight.push_back (param.boundary_weight); - for (unsigned i = 0; i < data_list[n1].interior.size (); i++) + for (size_t i = 0; i < data_list[n1].interior.size (); i++) data_list[n1].interior_weight.push_back (param.interior_weight); - for (unsigned i = 0; i < param.fit_iter; i++) + for (size_t i = 0; i < param.fit_iter; i++) { fit.assemble (paramFP); fit.solve (); diff --git a/surface/src/on_nurbs/fitting_curve_2d.cpp b/surface/src/on_nurbs/fitting_curve_2d.cpp index 1a948df9b1d..399097acbf1 100644 --- a/surface/src/on_nurbs/fitting_curve_2d.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d.cpp @@ -74,7 +74,7 @@ FittingCurve2d::findElement (double xi, const std::vector &elements) if (xi >= elements.back ()) return (int (elements.size ()) - 2); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { if (xi >= elements[i] && xi < elements[i + 1]) { @@ -94,10 +94,10 @@ FittingCurve2d::refine () std::vector elements = getElementVector (m_nurbs); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) m_nurbs.InsertKnot (xi[i], 1); } @@ -160,7 +160,7 @@ FittingCurve2d::addControlPointConstraint (int i, const Eigen::Vector2d &f, doub // add constraint for control point m_solver.f (row, 0, f (0) * weight); m_solver.f (row, 1, f (1) * weight); - for (int j = 0; j < cols; j++) + for (unsigned j = 0; j < cols; j++) m_solver.K (row, j, 0.0); m_solver.K (row, i, weight); } @@ -516,7 +516,7 @@ FittingCurve2d::inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vecto error = DBL_MAX; int is_corner (-1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { Eigen::Vector2d p1; nurbs.Evaluate (elements[i], 0, 2, &p1 (0)); @@ -674,7 +674,7 @@ FittingCurve2d::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Ei std::vector elements = pcl::on_nurbs::FittingCurve2d::getElementVector (nurbs); double seg = 1.0 / (nurbs.Order () - 1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double &xi0 = elements[i]; double &xi1 = elements[i + 1]; @@ -717,7 +717,7 @@ FittingCurve2d::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Ei double d_shortest (DBL_MAX); double seg = 1.0 / (nurbs.Order () - 1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double &xi0 = elements[i]; double &xi1 = elements[i + 1]; diff --git a/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp index e84add2bf43..7e5069dac91 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_apdm.cpp @@ -75,7 +75,7 @@ FittingCurve2dAPDM::findElement (double xi, const std::vector &elements) if (xi >= elements.back ()) return (int (elements.size ()) - 2); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { if (xi >= elements[i] && xi < elements[i + 1]) { @@ -95,10 +95,10 @@ FittingCurve2dAPDM::refine () std::vector elements = getElementVector (m_nurbs); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) m_nurbs.InsertKnot (xi[i], 1); } @@ -241,7 +241,7 @@ FittingCurve2dAPDM::addCPsOnClosestPointViolation (double max_error) //int nknots (0); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { bool inserted (false); @@ -333,7 +333,7 @@ FittingCurve2dAPDM::removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curv nurbs_opt.m_knot[cp_red] = 0.0; nurbs_opt.m_knot[nurbs_opt.m_knot_capacity - cp_red - 1] = 1.0; - for (unsigned j = 0; j < cps.size (); j++) + for (size_t j = 0; j < cps.size (); j++) nurbs_opt.SetCV (j + cp_red, cps[j]); for (int j = 0; j < cp_red; j++) @@ -514,7 +514,7 @@ FittingCurve2dAPDM::initCPsNurbsCurve2D (int order, const vector_vec2d &cps) nurbs = ON_NurbsCurve (2, false, order, ncps); nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1)); - for (int j = 0; j < cps.size (); j++) + for (size_t j = 0; j < cps.size (); j++) nurbs.SetCV (cp_red + j, ON_3dPoint (cps[j] (0), cps[j] (1), 0.0)); // close nurbs @@ -747,9 +747,9 @@ FittingCurve2dAPDM::assembleClosestPoints (const std::vector &elements, double ds = 1.0 / (2.0 * sigma2); double seg = 1.0 / (samples_per_element + 1); - for (unsigned i = 0; i < elements.size (); i++) + for (size_t i = 0; i < elements.size (); i++) { - int k = i % int (elements.size ()); + size_t k = i % elements.size (); double xi0 = elements[i]; double dxi = elements[k] - xi0; @@ -889,7 +889,7 @@ FittingCurve2dAPDM::inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::V error = DBL_MAX; int is_corner (-1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { Eigen::Vector2d p1; nurbs.Evaluate (elements[i], 0, 2, &p1 (0)); @@ -1047,7 +1047,7 @@ FittingCurve2dAPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, cons std::vector elements = pcl::on_nurbs::FittingCurve2dAPDM::getElementVector (nurbs); double seg = 1.0 / (nurbs.Order () - 1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double &xi0 = elements[i]; double &xi1 = elements[i + 1]; @@ -1090,13 +1090,13 @@ FittingCurve2dAPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, cons double d_shortest (DBL_MAX); double seg = 1.0 / (nurbs.Order () - 1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double &xi0 = elements[i]; double &xi1 = elements[i + 1]; double dxi = xi1 - xi0; - for (unsigned j = 0; j < nurbs.Order (); j++) + for (size_t j = 0; j < nurbs.Order (); j++) { double xi = xi0 + (seg * j) * dxi; diff --git a/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp index f656e3e48dd..b66f4c52a66 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_asdm.cpp @@ -406,7 +406,7 @@ FittingCurve2dASDM::assembleClosestPoints (const std::vector &elements, double ds = 1.0 / (2.0 * sigma2); - for (unsigned i = 0; i < elements.size (); i++) + for (size_t i = 0; i < elements.size (); i++) { int j = (i + 1) % int (elements.size ()); diff --git a/surface/src/on_nurbs/fitting_curve_2d_atdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_atdm.cpp index 334160e0ae4..bac22fe2407 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_atdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_atdm.cpp @@ -321,7 +321,7 @@ FittingCurve2dATDM::assembleClosestPoints (const std::vector &elements, double ds = 1.0 / (2.0 * sigma2); - for (unsigned i = 0; i < elements.size (); i++) + for (size_t i = 0; i < elements.size (); i++) { int j = i % int (elements.size ()); diff --git a/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp b/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp index 83de9d2c031..238029bb4fd 100644 --- a/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_2d_pdm.cpp @@ -75,7 +75,7 @@ FittingCurve2dPDM::findElement (double xi, const std::vector &elements) if (xi >= elements.back ()) return (int (elements.size ()) - 2); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { if (xi >= elements[i] && xi < elements[i + 1]) { @@ -95,10 +95,10 @@ FittingCurve2dPDM::refine () std::vector elements = getElementVector (m_nurbs); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) m_nurbs.InsertKnot (xi[i], 1); } @@ -208,7 +208,7 @@ FittingCurve2dPDM::addCPsOnClosestPointViolation (double max_error) //int nknots (0); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { bool inserted (false); @@ -300,7 +300,7 @@ FittingCurve2dPDM::removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curve nurbs_opt.m_knot[cp_red] = 0.0; nurbs_opt.m_knot[nurbs_opt.m_knot_capacity - cp_red - 1] = 1.0; - for (unsigned j = 0; j < cps.size (); j++) + for (size_t j = 0; j < cps.size (); j++) nurbs_opt.SetCV (j + cp_red, cps[j]); for (int j = 0; j < cp_red; j++) @@ -375,7 +375,7 @@ FittingCurve2dPDM::initCPsNurbsCurve2D (int order, const vector_vec2d &cps) nurbs = ON_NurbsCurve (2, false, order, ncps); nurbs.MakePeriodicUniformKnotVector (1.0 / (ncps - order + 1)); - for (int j = 0; j < cps.size (); j++) + for (size_t j = 0; j < cps.size (); j++) nurbs.SetCV (cp_red + j, ON_3dPoint (cps[j] (0), cps[j] (1), 0.0)); // close nurbs @@ -646,7 +646,7 @@ FittingCurve2dPDM::inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Ve error = DBL_MAX; int is_corner (-1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { Eigen::Vector2d p1; nurbs.Evaluate (elements[i], 0, 2, &p1 (0)); @@ -804,7 +804,7 @@ FittingCurve2dPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const std::vector elements = pcl::on_nurbs::FittingCurve2dPDM::getElementVector (nurbs); double seg = 1.0 / (nurbs.Order () - 1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double &xi0 = elements[i]; double &xi1 = elements[i + 1]; @@ -847,7 +847,7 @@ FittingCurve2dPDM::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const double d_shortest (DBL_MAX); double seg = 1.0 / (nurbs.Order () - 1); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double &xi0 = elements[i]; double &xi1 = elements[i + 1]; diff --git a/surface/src/on_nurbs/fitting_curve_pdm.cpp b/surface/src/on_nurbs/fitting_curve_pdm.cpp index 758d311051a..9cfbe1b7c2b 100644 --- a/surface/src/on_nurbs/fitting_curve_pdm.cpp +++ b/surface/src/on_nurbs/fitting_curve_pdm.cpp @@ -75,7 +75,7 @@ FittingCurve::findElement (double xi, const std::vector &elements) if (xi >= elements.back ()) return (int (elements.size ()) - 2); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { if (xi >= elements[i] && xi < elements[i + 1]) { @@ -95,10 +95,10 @@ FittingCurve::refine () std::vector elements = getElementVector (m_nurbs); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) m_nurbs.InsertKnot (xi[i], 1); } @@ -422,7 +422,7 @@ FittingCurve::findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eige double d_shortest (DBL_MAX); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]); diff --git a/surface/src/on_nurbs/fitting_cylinder_pdm.cpp b/surface/src/on_nurbs/fitting_cylinder_pdm.cpp index 6b805ed4ebd..4f8d595bedc 100644 --- a/surface/src/on_nurbs/fitting_cylinder_pdm.cpp +++ b/surface/src/on_nurbs/fitting_cylinder_pdm.cpp @@ -81,10 +81,10 @@ FittingCylinder::refine (int dim) std::vector xi; std::vector elements = getElementVector (m_nurbs, dim); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) m_nurbs.InsertKnot (dim, xi[i], 1); } @@ -95,13 +95,13 @@ FittingCylinder::refine (int dim, double param) if (param == elements[elements.size () - 1]) { - int i = int (elements.size ()) - 2; + size_t i = elements.size () - 2; double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]); m_nurbs.InsertKnot (dim, xi); return; } - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { if (param >= elements[i] && param < elements[i + 1]) { @@ -614,9 +614,9 @@ FittingCylinder::findClosestElementMidPoint (const ON_NurbsSurface &nurbs, const std::vector elementsV = getElementVector (nurbs, 1); double d_shortest = std::numeric_limits::max (); - for (unsigned i = 0; i < elementsU.size () - 1; i++) + for (size_t i = 0; i < elementsU.size () - 1; i++) { - for (unsigned j = 0; j < elementsV.size () - 1; j++) + for (size_t j = 0; j < elementsV.size () - 1; j++) { double points[3]; diff --git a/surface/src/on_nurbs/fitting_sphere_pdm.cpp b/surface/src/on_nurbs/fitting_sphere_pdm.cpp index e1a2ff82776..42eb2a05c45 100644 --- a/surface/src/on_nurbs/fitting_sphere_pdm.cpp +++ b/surface/src/on_nurbs/fitting_sphere_pdm.cpp @@ -168,7 +168,7 @@ FittingSphere::initNurbsSphere (int order, NurbsDataSurface *data, Eigen::Vector Eigen::Vector3d _min (DBL_MAX, DBL_MAX, DBL_MAX); Eigen::Vector3d _max (-DBL_MAX, -DBL_MAX, -DBL_MAX); - for (int i = 0; i < data->interior.size (); i++) + for (size_t i = 0; i < data->interior.size (); i++) { Eigen::Vector3d p = data->interior[i] - mean; @@ -515,9 +515,9 @@ FittingSphere::findClosestElementMidPoint (const ON_NurbsSurface &nurbs, const V std::vector elementsV = getElementVector (nurbs, 1); double d_shortest = std::numeric_limits::max (); - for (unsigned i = 0; i < elementsU.size () - 1; i++) + for (size_t i = 0; i < elementsU.size () - 1; i++) { - for (unsigned j = 0; j < elementsV.size () - 1; j++) + for (size_t j = 0; j < elementsV.size () - 1; j++) { double points[3]; diff --git a/surface/src/on_nurbs/fitting_surface_im.cpp b/surface/src/on_nurbs/fitting_surface_im.cpp index f42a5d00f64..a90667aac16 100644 --- a/surface/src/on_nurbs/fitting_surface_im.cpp +++ b/surface/src/on_nurbs/fitting_surface_im.cpp @@ -157,7 +157,7 @@ FittingSurfaceIM::refine () { int dim = 0; std::vector elements = getElementVector (m_nurbs, dim); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]); m_nurbs.InsertKnot (dim, xi, 1); @@ -166,7 +166,7 @@ FittingSurfaceIM::refine () { int dim = 1; std::vector elements = getElementVector (m_nurbs, dim); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) { double xi = elements[i] + 0.5 * (elements[i + 1] - elements[i]); m_nurbs.InsertKnot (dim, xi, 1); @@ -521,9 +521,9 @@ FittingSurfaceIM::findClosestElementMidPoint (const ON_NurbsSurface &nurbs, cons std::vector elementsV = getElementVector (nurbs, 1); double d_shortest (DBL_MAX); - for (unsigned i = 0; i < elementsU.size () - 1; i++) + for (size_t i = 0; i < elementsU.size () - 1; i++) { - for (unsigned j = 0; j < elementsV.size () - 1; j++) + for (size_t j = 0; j < elementsV.size () - 1; j++) { double points[3]; double d; diff --git a/surface/src/on_nurbs/fitting_surface_pdm.cpp b/surface/src/on_nurbs/fitting_surface_pdm.cpp index 7324f7989ce..d47b4a12ff1 100644 --- a/surface/src/on_nurbs/fitting_surface_pdm.cpp +++ b/surface/src/on_nurbs/fitting_surface_pdm.cpp @@ -86,10 +86,10 @@ FittingSurface::refine (int dim) std::vector xi; std::vector elements = getElementVector (m_nurbs, dim); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) m_nurbs.InsertKnot (dim, xi[i], 1); m_elementsU = getElementVector (m_nurbs, 0); @@ -106,10 +106,10 @@ FittingSurface::refine (ON_NurbsSurface &nurbs, int dim) std::vector xi; std::vector elements = getElementVector (nurbs, dim); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) nurbs.InsertKnot (dim, xi[i], 1); } @@ -1120,9 +1120,9 @@ FittingSurface::findClosestElementMidPoint (const ON_NurbsSurface &nurbs, const std::vector elementsV = getElementVector (nurbs, 1); double d_shortest (DBL_MAX); - for (unsigned i = 0; i < elementsU.size () - 1; i++) + for (size_t i = 0; i < elementsU.size () - 1; i++) { - for (unsigned j = 0; j < elementsV.size () - 1; j++) + for (size_t j = 0; j < elementsV.size () - 1; j++) { double points[3]; double d; @@ -1164,20 +1164,20 @@ FittingSurface::inverseMappingBoundary (const ON_NurbsSurface &nurbs, const Vect std::vector elementsV = getElementVector (nurbs, 1); // NORTH - SOUTH - for (unsigned i = 0; i < (elementsV.size () - 1); i++) + for (size_t i = 0; i < (elementsV.size () - 1); i++) { ini_points.emplace_back(WEST, elementsV[i] + 0.5 * (elementsV[i + 1] - elementsV[i])); ini_points.emplace_back(EAST, elementsV[i] + 0.5 * (elementsV[i + 1] - elementsV[i])); } // WEST - EAST - for (unsigned i = 0; i < (elementsU.size () - 1); i++) + for (size_t i = 0; i < (elementsU.size () - 1); i++) { ini_points.emplace_back(NORTH, elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i])); ini_points.emplace_back(SOUTH, elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i])); } - for (unsigned i = 0; i < ini_points.size (); i++) + for (size_t i = 0; i < ini_points.size (); i++) { Vector2d params = inverseMappingBoundary (nurbs, pt, ini_points[i].side, ini_points[i].hint, err_tmp, p_tmp, diff --git a/surface/src/on_nurbs/global_optimization_pdm.cpp b/surface/src/on_nurbs/global_optimization_pdm.cpp index 2b110638f5d..7e01ed07ec1 100644 --- a/surface/src/on_nurbs/global_optimization_pdm.cpp +++ b/surface/src/on_nurbs/global_optimization_pdm.cpp @@ -115,7 +115,7 @@ GlobalOptimization::assemble (Parameter params) m_solver.assign (m_nrows, m_ncols, 3); - for (unsigned i = 0; i < m_data.size (); i++) + for (size_t i = 0; i < m_data.size (); i++) m_data[i]->common_boundary_param.clear (); // assemble matrix @@ -159,7 +159,7 @@ GlobalOptimization::updateSurf (double damp) { int ncps (0); - for (unsigned i = 0; i < m_nurbs.size (); i++) + for (size_t i = 0; i < m_nurbs.size (); i++) { ON_NurbsSurface* nurbs = m_nurbs[i]; @@ -199,10 +199,10 @@ GlobalOptimization::refine (unsigned id, int dim) std::vector xi; std::vector elements = FittingSurface::getElementVector (*m_nurbs[id], dim); - for (unsigned i = 0; i < elements.size () - 1; i++) + for (size_t i = 0; i < elements.size () - 1; i++) xi.push_back (elements[i] + 0.5 * (elements[i + 1] - elements[i])); - for (unsigned i = 0; i < xi.size (); i++) + for (size_t i = 0; i < xi.size (); i++) { m_nurbs[id]->InsertKnot (dim, xi[i], 1); } @@ -234,7 +234,7 @@ GlobalOptimization::assembleCommonBoundaries (unsigned id1, double weight, unsig if (nurbs1->Order (0) != nurbs1->Order (1)) printf ("[GlobalOptimization::assembleCommonBoundaries] Warning, order in u and v direction differ (nurbs1).\n"); - for (unsigned i = 0; i < data1->common_boundary_point.size (); i++) + for (size_t i = 0; i < data1->common_boundary_point.size (); i++) { Eigen::Vector3d p1, tu1, tv1, p2, tu2, tv2, t1, t2; Eigen::Vector2d params1, params2; @@ -325,12 +325,12 @@ GlobalOptimization::assembleClosingBoundaries (unsigned id, unsigned samples, do ClosingBoundary::sampleFromBoundary (nurbs1, boundary1, params1, samples); // for each other nurbs - for (unsigned n2 = (id + 1); n2 < m_nurbs.size (); n2++) + for (size_t n2 = (id + 1); n2 < m_nurbs.size (); n2++) { ON_NurbsSurface *nurbs2 = m_nurbs[n2]; // find closest point to boundary - for (unsigned i = 0; i < boundary1.size (); i++) + for (size_t i = 0; i < boundary1.size (); i++) { double error; Eigen::Vector3d p, tu, tv; @@ -359,7 +359,7 @@ GlobalOptimization::assembleInteriorPoints (unsigned id, int ncps, double weight ON_NurbsSurface *nurbs = m_nurbs[id]; NurbsDataSurface *data = m_data[id]; - unsigned nInt = static_cast (m_data[id]->interior.size ()); + size_t interiorSize = m_data[id]->interior.size (); // interior points should lie on surface data->interior_line_start.clear (); @@ -368,7 +368,7 @@ GlobalOptimization::assembleInteriorPoints (unsigned id, int ncps, double weight data->interior_normals.clear (); // data->interior_param.clear(); - for (unsigned p = 0; p < nInt; p++) + for (size_t p = 0; p < interiorSize; p++) { Vector3d pcp; pcp (0) = data->interior[p] (0); diff --git a/surface/src/on_nurbs/global_optimization_tdm.cpp b/surface/src/on_nurbs/global_optimization_tdm.cpp index 83f627ad3f0..17f4f14dad5 100644 --- a/surface/src/on_nurbs/global_optimization_tdm.cpp +++ b/surface/src/on_nurbs/global_optimization_tdm.cpp @@ -90,7 +90,7 @@ GlobalOptimizationTDM::assemble (Parameter params) m_solver.assign (m_nrows, m_ncols, 1); - for (unsigned i = 0; i < m_data.size (); i++) + for (size_t i = 0; i < m_data.size (); i++) m_data[i]->common_boundary_param.clear (); // assemble matrix @@ -208,7 +208,7 @@ GlobalOptimizationTDM::updateSurf (double damp) { int ncps (0); - for (unsigned i = 0; i < m_nurbs.size (); i++) + for (size_t i = 0; i < m_nurbs.size (); i++) { ON_NurbsSurface* nurbs = m_nurbs[i]; @@ -276,7 +276,7 @@ GlobalOptimizationTDM::assembleCommonBoundaries (unsigned id1, double weight, un if (nurbs1->m_order[0] != nurbs1->m_order[1]) printf ("[GlobalOptimizationTDM::assembleCommonBoundaries] Warning, order in u and v direction differ (nurbs1).\n"); - for (unsigned i = 0; i < data1->common_boundary_point.size (); i++) + for (size_t i = 0; i < data1->common_boundary_point.size (); i++) { Eigen::Vector3d p0 = data1->common_boundary_point[i]; Eigen::Vector2i id (id1, data1->common_boundary_idx[i]); @@ -368,12 +368,12 @@ GlobalOptimizationTDM::assembleClosingBoundaries (unsigned id, unsigned samples, ClosingBoundary::sampleFromBoundary (nurbs1, boundary1, params1, samples); // for each other nurbs - for (unsigned n2 = (id + 1); n2 < m_nurbs.size (); n2++) + for (size_t n2 = (id + 1); n2 < m_nurbs.size (); n2++) { ON_NurbsSurface *nurbs2 = m_nurbs[n2]; // find closest point to boundary - for (unsigned i = 0; i < boundary1.size (); i++) + for (size_t i = 0; i < boundary1.size (); i++) { double error; Eigen::Vector3d p, tu, tv; @@ -412,14 +412,14 @@ GlobalOptimizationTDM::assembleClosingBoundariesTD (unsigned id, unsigned sample // for each other nurbs // for (unsigned n2 = (id + 1); n2 < m_nurbs.size(); n2++) { - for (unsigned n2 = 0; n2 < m_nurbs.size (); n2++) + for (size_t n2 = 0; n2 < m_nurbs.size (); n2++) { if (id == n2) continue; ON_NurbsSurface *nurbs2 = m_nurbs[n2]; // find closest point to boundary - for (unsigned i = 0; i < boundary1.size (); i++) + for (size_t i = 0; i < boundary1.size (); i++) { double error; Eigen::Vector3d p, n, tu, tv; diff --git a/surface/src/on_nurbs/nurbs_solve_eigen.cpp b/surface/src/on_nurbs/nurbs_solve_eigen.cpp index 503febe4740..1aa82260155 100644 --- a/surface/src/on_nurbs/nurbs_solve_eigen.cpp +++ b/surface/src/on_nurbs/nurbs_solve_eigen.cpp @@ -94,9 +94,9 @@ NurbsSolve::resize (unsigned rows) void NurbsSolve::printK () { - for (unsigned r = 0; r < m_Keig.rows (); r++) + for (Eigen::Index r = 0; r < m_Keig.rows (); r++) { - for (unsigned c = 0; c < m_Keig.cols (); c++) + for (Eigen::Index c = 0; c < m_Keig.cols (); c++) { printf (" %f", m_Keig (r, c)); } @@ -107,9 +107,9 @@ NurbsSolve::printK () void NurbsSolve::printX () { - for (unsigned r = 0; r < m_xeig.rows (); r++) + for (Eigen::Index r = 0; r < m_xeig.rows (); r++) { - for (unsigned c = 0; c < m_xeig.cols (); c++) + for (Eigen::Index c = 0; c < m_xeig.cols (); c++) { printf (" %f", m_xeig (r, c)); } @@ -120,9 +120,9 @@ NurbsSolve::printX () void NurbsSolve::printF () { - for (unsigned r = 0; r < m_feig.rows (); r++) + for (Eigen::Index r = 0; r < m_feig.rows (); r++) { - for (unsigned c = 0; c < m_feig.cols (); c++) + for (Eigen::Index c = 0; c < m_feig.cols (); c++) { printf (" %f", m_feig (r, c)); } diff --git a/surface/src/on_nurbs/nurbs_tools.cpp b/surface/src/on_nurbs/nurbs_tools.cpp index 9c1a153e1cc..5246b764ecf 100644 --- a/surface/src/on_nurbs/nurbs_tools.cpp +++ b/surface/src/on_nurbs/nurbs_tools.cpp @@ -89,9 +89,9 @@ NurbsTools::getClosestPoint (const Eigen::Vector2d &p, const vector_vec2d &data) if (data.empty ()) throw std::runtime_error ("[NurbsTools::getClosestPoint(2d)] Data empty.\n"); - unsigned idx (0); + size_t idx = 0; double dist2 (DBL_MAX); - for (unsigned i = 0; i < data.size (); i++) + for (size_t i = 0; i < data.size (); i++) { double d2 = (data[i] - p).squaredNorm (); if (d2 < dist2) @@ -109,9 +109,9 @@ NurbsTools::getClosestPoint (const Eigen::Vector3d &p, const vector_vec3d &data) if (data.empty ()) throw std::runtime_error ("[NurbsTools::getClosestPoint(2d)] Data empty.\n"); - unsigned idx (0); + size_t idx = 0; double dist2 (DBL_MAX); - for (unsigned i = 0; i < data.size (); i++) + for (size_t i = 0; i < data.size (); i++) { double d2 = (data[i] - p).squaredNorm (); if (d2 < dist2) @@ -130,11 +130,11 @@ NurbsTools::getClosestPoint (const Eigen::Vector2d &p, const Eigen::Vector2d &di if (data.empty ()) throw std::runtime_error ("[NurbsTools::getClosestPoint(2d)] Data empty.\n"); - unsigned idx (0); + size_t idx = 0; idxcp = 0; double dist2 (0.0); double dist2cp (DBL_MAX); - for (unsigned i = 0; i < data.size (); i++) + for (size_t i = 0; i < data.size (); i++) { Eigen::Vector2d v = (data[i] - p); double d2 = v.squaredNorm (); diff --git a/surface/src/on_nurbs/sequential_fitter.cpp b/surface/src/on_nurbs/sequential_fitter.cpp index 9b4c17e997f..fb66a6b1c07 100644 --- a/surface/src/on_nurbs/sequential_fitter.cpp +++ b/surface/src/on_nurbs/sequential_fitter.cpp @@ -593,7 +593,7 @@ SequentialFitter::grow (float max_dist, float max_angle, unsigned min_length, un double int_err (0.0); double div_err = 1.0 / double (m_data.interior_error.size ()); - for (unsigned i = 0; i < m_data.interior_error.size (); i++) + for (size_t i = 0; i < m_data.interior_error.size (); i++) { int_err += (m_data.interior_error[i] * div_err); } @@ -608,9 +608,9 @@ unsigned SequentialFitter::PCL2ON (pcl::PointCloud::Ptr &pcl_cloud, const std::vector &indices, vector_vec3d &on_cloud) { - unsigned numPoints (0); + size_t numPoints = 0; - for (unsigned i = 0; i < indices.size (); i++) + for (size_t i = 0; i < indices.size (); i++) { pcl::PointXYZRGB &pt = pcl_cloud->at (indices[i]); diff --git a/surface/src/on_nurbs/triangulation.cpp b/surface/src/on_nurbs/triangulation.cpp index 2ad20cef76c..978913c1cd4 100644 --- a/surface/src/on_nurbs/triangulation.cpp +++ b/surface/src/on_nurbs/triangulation.cpp @@ -182,7 +182,7 @@ Triangulation::convertSurface2PolygonMesh (const ON_NurbsSurface &nurbs, Polygon createVertices (cloud, float (x0), float (y0), 0.0f, float (w), float (h), resolution, resolution); createIndices (mesh.polygons, 0, resolution, resolution); - for (unsigned i = 0; i < cloud->size (); i++) + for (size_t i = 0; i < cloud->size (); i++) { pcl::PointXYZ &v = cloud->at (i); @@ -232,7 +232,7 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, std::vector out_idx; pcl::on_nurbs::vector_vec2d out_pc; - for (unsigned i = 0; i < cloud->size (); i++) + for (size_t i = 0; i < cloud->size (); i++) { double err; Eigen::Vector2d pc, tc; @@ -255,7 +255,7 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, pt_is_in[i] = (z (2) >= 0.0); } - for (unsigned i = 0; i < polygons.size (); i++) + for (size_t i = 0; i < polygons.size (); i++) { unsigned in (0); pcl::Vertices &poly = polygons[i]; @@ -358,7 +358,7 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, pcl::on_nurbs::NurbsTools::computeBoundingBox (curve, a0, a1); double rScale = 1.0 / pcl::on_nurbs::NurbsTools::computeRScale (a0, a1); - for (unsigned i = 0; i < cloud->size (); i++) + for (size_t i = 0; i < cloud->size (); i++) { double err, param; Eigen::Vector2d pc, tc; @@ -385,7 +385,7 @@ Triangulation::convertTrimmedSurface2PolygonMesh (const ON_NurbsSurface &nurbs, start.push_back (Eigen::Vector3d (vp (0), vp (1), 0.0)); } - for (unsigned i = 0; i < polygons.size (); i++) + for (size_t i = 0; i < polygons.size (); i++) { unsigned in (0); pcl::Vertices &poly = polygons[i]; @@ -483,7 +483,7 @@ Triangulation::convertSurface2Vertices (const ON_NurbsSurface &nurbs, pcl::Point createVertices (cloud, float (x0), float (y0), 0.0f, float (w), float (h), resolution, resolution); createIndices (vertices, 0, resolution, resolution); - for (unsigned i = 0; i < cloud->size (); i++) + for (size_t i = 0; i < cloud->size (); i++) { pcl::PointXYZ &v = cloud->at (i); diff --git a/surface/src/vtk_smoothing/vtk_utils.cpp b/surface/src/vtk_smoothing/vtk_utils.cpp index 5855215001e..fe2675ff005 100644 --- a/surface/src/vtk_smoothing/vtk_utils.cpp +++ b/surface/src/vtk_smoothing/vtk_utils.cpp @@ -162,7 +162,7 @@ pcl::VTKUtils::vtk2mesh (const vtkSmartPointer& poly_data, pcl::Pol while (mesh_polygons->GetNextCell (nr_cell_points, cell_points)) { mesh.polygons[id_poly].vertices.resize (nr_cell_points); - for (int i = 0; i < nr_cell_points; ++i) + for (vtkIdType i = 0; i < nr_cell_points; ++i) mesh.polygons[id_poly].vertices[i] = static_cast (cell_points[i]); ++id_poly; } diff --git a/test/common/test_gaussian.cpp b/test/common/test_gaussian.cpp index 062ff9b5a75..6b589b4fd62 100644 --- a/test/common/test_gaussian.cpp +++ b/test/common/test_gaussian.cpp @@ -51,16 +51,16 @@ TEST(PCL, GaussianKernel) // Test kernel only version gk.compute(5, computed_kernel); EXPECT_EQ(kernel.size (), computed_kernel.size ()); - for(int i = 0; i < kernel.size (); i++) + for(Eigen::Index i = 0; i < kernel.size (); i++) EXPECT_NEAR(kernel[i], computed_kernel[i], 1e-4); // Test kernel and derivative version gk.compute(5, computed_kernel, computed_derivative); EXPECT_EQ(kernel.size (), computed_kernel.size ()); - for(int i = 0; i < kernel.size (); i++) + for(Eigen::Index i = 0; i < kernel.size (); i++) EXPECT_NEAR(kernel[i], computed_kernel[i], 1e-4); EXPECT_EQ(derivative.size (), computed_derivative.size ()); - for(int i = 0; i < derivative.size (); i++) + for(Eigen::Index i = 0; i < derivative.size (); i++) EXPECT_NEAR(derivative[i], computed_derivative[i], 1e-4); } diff --git a/test/common/test_vector_average.cpp b/test/common/test_vector_average.cpp index 54ca7c9ca57..d8a7cb04da1 100644 --- a/test/common/test_vector_average.cpp +++ b/test/common/test_vector_average.cpp @@ -56,7 +56,7 @@ TEST (PCL, VectorAverage_mean) Eigen::Vector3f correct_mean (0.0f, 0.0f, 0.0f); float weigth_sum = 0.0f; - for (unsigned int i = 0; i < points.size (); ++i) + for (size_t i = 0; i < points.size (); ++i) { correct_mean += weights[i]*points[i]; weigth_sum += weights[i]; @@ -64,7 +64,7 @@ TEST (PCL, VectorAverage_mean) correct_mean /= weigth_sum; pcl::VectorAverage va; - for (unsigned int i=0; i ne; cloud_organized_normal.reserve (cloud_organized_nonan.size ()); - for (unsigned int i = 0; i < cloud_organized_nonan.size (); ++i) + for (size_t i = 0; i < cloud_organized_nonan.size (); ++i) { // Output point pcl::PointXYZRGBNormal normali; @@ -2257,7 +2257,7 @@ TEST (NormalRefinement, Filters) int num_nans = 0; // Loop - for (unsigned int i = 0; i < idx_table.size (); ++i) + for (size_t i = 0; i < idx_table.size (); ++i) { float tmp; @@ -2301,13 +2301,13 @@ TEST (NormalRefinement, Filters) // Error variance of estimated float err_est_var = 0.0f; - for (unsigned int i = 0; i < errs_est.size (); ++i) + for (size_t i = 0; i < errs_est.size (); ++i) err_est_var = (errs_est[i] - err_est_mean) * (errs_est[i] - err_est_mean); err_est_var /= static_cast (errs_est.size () - 1); // Error variance of refined float err_refined_var = 0.0f; - for (unsigned int i = 0; i < errs_refined.size (); ++i) + for (size_t i = 0; i < errs_refined.size (); ++i) err_refined_var = (errs_refined[i] - err_refined_mean) * (errs_refined[i] - err_refined_mean); err_refined_var /= static_cast (errs_refined.size () - 1); diff --git a/test/geometry/test_mesh.cpp b/test/geometry/test_mesh.cpp index d06623ac7dd..34214a4a64f 100644 --- a/test/geometry/test_mesh.cpp +++ b/test/geometry/test_mesh.cpp @@ -92,7 +92,7 @@ TEST (TestAddDeleteFace, NonManifold1) vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear (); // 0 vi.push_back (VI (2)); vi.push_back (VI (1)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear (); // 1 vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (5)); faces.push_back (vi); vi.clear (); // 2 - for (unsigned int i=0; i > expected (faces.size ()); - for (unsigned int i=0; i tmp (faces [i].size ()); - for (unsigned int j=0; j tmp (faces [i].size ()); - for (unsigned int j=0; j tmp (faces [i].size ()); - for (unsigned int j=0; j & } VertexIndices vi; - for (unsigned int i=0; i & return (false); } if (verbose) std::cerr << "\texpected: "; - for (unsigned int j=0; j > &faces, cons const VertexDataCloud& vdc = mesh.getVertexDataCloud (); std::vector vv; - for (unsigned int i=0; i > &faces, cons return (false); } if (verbose) std::cerr << "\texpected: "; - for (unsigned int j=0; j ordered_faces; - for (unsigned int j=0; j fip; fip = mesh.addTrianglePair (faces [i]); @@ -549,7 +549,7 @@ TEST (TestManifoldTriangleMesh, addTrianglePair) ASSERT_TRUE (fip.second.isValid ()); } - for (unsigned int i=0; i brute_force_result; - for (unsigned int i=0; i k_indices; diff --git a/test/octree/test_octree.cpp b/test/octree/test_octree.cpp index f4fd4e021f1..84e7e49192c 100644 --- a/test/octree/test_octree.cpp +++ b/test/octree/test_octree.cpp @@ -207,7 +207,7 @@ TEST (PCL, Octree_Test) ASSERT_EQ (leafVectorB.size (), octreeB.getLeafCount ()); ASSERT_EQ (leafVectorA.size (), leafVectorB.size ()); - for (unsigned int i = 0; i < leafVectorB.size (); i++) + for (size_t i = 0; i < leafVectorB.size (); i++) { ASSERT_EQ (*leafVectorA[i], *leafVectorB[i]); } @@ -523,7 +523,7 @@ TEST (PCL, Octree2Buf_Test) ASSERT_EQ (leafVectorB.size (), octreeB.getLeafCount ()); ASSERT_EQ (leafVectorA.size (), leafVectorB.size ()); - for (unsigned int i = 0; i < leafVectorB.size (); i++) + for (size_t i = 0; i < leafVectorB.size (); i++) { ASSERT_EQ (*leafVectorA[i], *leafVectorB[i]); } @@ -603,7 +603,7 @@ TEST (PCL, Octree2Buf_Base_Double_Buffering_Test) ASSERT_EQ (leafVectorA.size (), leafVectorB.size ()); // check if octree octree structure is consistent. - for (unsigned int i = 0; i < leafVectorB.size (); i++) + for (size_t i = 0; i < leafVectorB.size (); i++) { ASSERT_EQ (*leafVectorA[i], *leafVectorB[i]); } @@ -671,7 +671,7 @@ TEST (PCL, Octree2Buf_Base_Double_Buffering_XOR_Test) ASSERT_EQ (treeBinaryA.size (), treeBinaryB.size ()); // check if octree octree structure is consistent. - for (unsigned int i = 0; i < leafVectorB.size (); i++) + for (size_t i = 0; i < leafVectorB.size (); i++) { ASSERT_EQ (*leafVectorA[i], *leafVectorB[i]); } diff --git a/test/registration/test_correspondence_estimation.cpp b/test/registration/test_correspondence_estimation.cpp index 447856df2ba..722b0e41e26 100644 --- a/test/registration/test_correspondence_estimation.cpp +++ b/test/registration/test_correspondence_estimation.cpp @@ -76,7 +76,7 @@ TEST (CorrespondenceEstimation, CorrespondenceEstimationNormalShooting) ce.determineCorrespondences (*corr); // Based on the data defined, the correspondence indices should be 1 <-> 1 , 2 <-> 2 , 3 <-> 3 etc. - for (unsigned int i = 0; i < corr->size (); i++) + for (size_t i = 0; i < corr->size (); i++) { EXPECT_EQ ((*corr)[i].index_query, (*corr)[i].index_match); } diff --git a/test/registration/test_correspondence_rejectors.cpp b/test/registration/test_correspondence_rejectors.cpp index a8d4193636a..a18bebedfe0 100644 --- a/test/registration/test_correspondence_rejectors.cpp +++ b/test/registration/test_correspondence_rejectors.cpp @@ -138,11 +138,11 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly) * Test criterion 2: expect high precision/recall. The true positives are the unscrambled correspondences * where the query/match index are equal. */ - unsigned int true_positives = 0; - for (unsigned int i = 0; i < result.size(); ++i) + size_t true_positives = 0; + for (size_t i = 0; i < result.size(); ++i) if (result[i].index_query == result[i].index_match) ++true_positives; - const unsigned int false_positives = static_cast (result.size()) - true_positives; + const size_t false_positives = result.size() - true_positives; const double precision = double(true_positives) / double(true_positives+false_positives); const double recall = double(true_positives) / double(size-last); diff --git a/test/sample_consensus/test_sample_consensus_plane_models.cpp b/test/sample_consensus/test_sample_consensus_plane_models.cpp index 0c9062773d9..f05f98ec12c 100644 --- a/test/sample_consensus/test_sample_consensus_plane_models.cpp +++ b/test/sample_consensus/test_sample_consensus_plane_models.cpp @@ -250,7 +250,7 @@ TEST (SampleConsensusModelNormalParallelPlane, RANSAC) cloud.points.resize (10); normals.resize (10); - for (unsigned idx = 0; idx < cloud.size (); ++idx) + for (size_t idx = 0; idx < cloud.size (); ++idx) { cloud.points[idx].x = static_cast ((rand () % 200) - 100); cloud.points[idx].y = static_cast ((rand () % 200) - 100); diff --git a/test/search/test_search.cpp b/test/search/test_search.cpp index 15bb02ac79e..e03051d64c5 100644 --- a/test/search/test_search.cpp +++ b/test/search/test_search.cpp @@ -164,7 +164,7 @@ bool testUniqueness (const vector& indices, const string& name) bool testOrder (const vector& distances, const string& name) { bool ordered = true; - for (unsigned idx1 = 1; idx1 < distances.size (); ++idx1) + for (size_t idx1 = 1; idx1 < distances.size (); ++idx1) { if (distances [idx1-1] > distances [idx1]) { @@ -254,7 +254,7 @@ bool compareResults (const std::vector& indices1, const::vector& dis } else { - for (unsigned idx = 0; idx < indices1.size (); ++idx) + for (size_t idx = 0; idx < indices1.size (); ++idx) { if (indices1[idx] != indices2[idx] && fabs (distances1[idx] - distances2[idx]) > eps) { @@ -406,7 +406,7 @@ testRadiusSearch (typename PointCloud::ConstPtr point_cloud, vectorgetName () << ": " << (passed[sIdx]?"passed":"failed") << endl; EXPECT_TRUE (passed [sIdx]); diff --git a/test/segmentation/test_random_walker.cpp b/test/segmentation/test_random_walker.cpp index fee79c7783d..ed611fa7968 100644 --- a/test/segmentation/test_random_walker.cpp +++ b/test/segmentation/test_random_walker.cpp @@ -173,7 +173,7 @@ TEST_P (RandomWalkerTest, BuildLinearSystem) std::vector degrees (g.rows, 0.0); std::vector L_sums (g.rows, 0.0); std::vector B_sums (g.rows, 0.0); - for (int k = 0; k < rw.L.outerSize (); ++k) + for (Eigen::Index k = 0; k < rw.L.outerSize (); ++k) { for (SparseMatrix::InnerIterator it (rw.L, k); it; ++it) { @@ -189,7 +189,7 @@ TEST_P (RandomWalkerTest, BuildLinearSystem) } } } - for (int k = 0; k < rw.B.outerSize (); ++k) + for (Eigen::Index k = 0; k < rw.B.outerSize (); ++k) { for (SparseMatrix::InnerIterator it (rw.B, k); it; ++it) { diff --git a/tools/tiff2pcd.cpp b/tools/tiff2pcd.cpp index 0293e4a932e..bd35d76bdbd 100644 --- a/tools/tiff2pcd.cpp +++ b/tools/tiff2pcd.cpp @@ -324,7 +324,7 @@ int main(int argc, char ** argv) sort (tiff_depth_files.begin (), tiff_depth_files.end ()); sort (tiff_depth_paths.begin (), tiff_depth_paths.end ()); - for(unsigned int i=0; i rgb_data; diff --git a/visualization/src/common/io.cpp b/visualization/src/common/io.cpp index e6022960e63..4bc65126ace 100644 --- a/visualization/src/common/io.cpp +++ b/visualization/src/common/io.cpp @@ -56,7 +56,7 @@ pcl::visualization::getCorrespondingPointCloud (vtkPolyData *src, cloud.height = 1; cloud.width = static_cast (src->GetNumberOfPoints ()); cloud.is_dense = false; cloud.points.resize (cloud.width * cloud.height); - for (int i = 0; i < src->GetNumberOfPoints (); i++) + for (vtkIdType i = 0; i < src->GetNumberOfPoints (); i++) { double p[3]; src->GetPoint (i, p); diff --git a/visualization/src/image_viewer.cpp b/visualization/src/image_viewer.cpp index daede7aac98..13f826f7332 100644 --- a/visualization/src/image_viewer.cpp +++ b/visualization/src/image_viewer.cpp @@ -386,7 +386,7 @@ pcl::visualization::ImageViewer::spinOnce (int time, bool force_redraw) interactor_->Start (); interactor_->DestroyTimer (exit_main_loop_timer_callback_->right_timer_id); ); - for(unsigned int i = 0; i < image_data_.size(); i++) + for(size_t i = 0; i < image_data_.size(); i++) delete [] image_data_[i]; image_data_.clear (); } @@ -871,7 +871,7 @@ void pcl::visualization::ImageViewer::render () { win_->Render (); - for(unsigned int i = 0; i < image_data_.size(); i++) + for(size_t i = 0; i < image_data_.size(); i++) delete [] image_data_[i]; image_data_.clear (); } diff --git a/visualization/src/pcl_plotter.cpp b/visualization/src/pcl_plotter.cpp index 29353ee54c2..36a201dfee5 100644 --- a/visualization/src/pcl_plotter.cpp +++ b/visualization/src/pcl_plotter.cpp @@ -158,7 +158,7 @@ pcl::visualization::PCLPlotter::addPlotData ( double *array_x = new double[plot_data.size ()]; double *array_y = new double[plot_data.size ()]; - for (unsigned int i = 0; i < plot_data.size (); i++) + for (size_t i = 0; i < plot_data.size (); i++) { array_x[i] = plot_data[i].first; array_y[i] = plot_data[i].second; diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index c35b74ff99e..5b20ac590ac 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -3276,7 +3276,7 @@ pcl::visualization::PCLVisualizer::addPolylineFromPolygonMesh ( { vtkSmartPointer polyLine = vtkSmartPointer::New(); polyLine->GetPointIds()->SetNumberOfIds(polymesh.polygons[i].vertices.size()); - for(unsigned int k = 0; k < polymesh.polygons[i].vertices.size(); k++) + for(size_t k = 0; k < polymesh.polygons[i].vertices.size(); k++) { polyLine->GetPointIds ()->SetId (k, polymesh.polygons[i].vertices[k]); } @@ -3713,7 +3713,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( 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); @@ -3918,7 +3918,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( if (!ids) return; 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 = static_cast (ids->GetValue (sel_id)); vtkCell * cell = polydata->GetCell (id_mesh); diff --git a/visualization/src/range_image_visualizer.cpp b/visualization/src/range_image_visualizer.cpp index 4e0758fd852..c6aa066b606 100644 --- a/visualization/src/range_image_visualizer.cpp +++ b/visualization/src/range_image_visualizer.cpp @@ -139,7 +139,7 @@ pcl::visualization::RangeImageVisualizer::getInterestPointsWidget ( RangeImageVisualizer* widget = new RangeImageVisualizer; widget->showFloatImage (interest_image, range_image.width, range_image.height, min_value, max_value); widget->setWindowTitle (name); - for (unsigned int i=0; i deviceManager = pcl::io::openni2::OpenNI2DeviceManager::getInstance (); if (deviceManager->getNumOfConnectedDevices () > 0) { - for (unsigned deviceIdx = 0; deviceIdx < deviceManager->getNumOfConnectedDevices (); ++deviceIdx) + for (size_t deviceIdx = 0; deviceIdx < deviceManager->getNumOfConnectedDevices (); ++deviceIdx) { boost::shared_ptr device = deviceManager->getDeviceByIndex (deviceIdx); cout << "Device " << device->getStringID () << "connected." << endl;