From 9684d2979b713a428f80744386f77c9d0c8b82f4 Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Thu, 26 Sep 2019 20:37:15 +0900 Subject: [PATCH] Deprecated getFieldIndex with first argument as cloud (#3365) Deprecate getFieldIndex() with first argument as cloud --- apps/src/pcd_select_object_plane.cpp | 2 +- common/include/pcl/common/impl/io.hpp | 17 +++++++--------- common/include/pcl/common/io.h | 8 ++++++-- .../sources/vfh_recognition/build_tree.cpp | 2 +- .../vfh_recognition/nearest_neighbors.cpp | 2 +- .../filters/impl/approximate_voxel_grid.hpp | 4 ++-- .../include/pcl/filters/impl/passthrough.hpp | 2 +- .../include/pcl/filters/impl/voxel_grid.hpp | 6 +++--- .../filters/impl/voxel_grid_covariance.hpp | 6 +++--- filters/src/voxel_grid_label.cpp | 8 ++++---- .../impl/octree_pointcloud_compression.hpp | 8 ++++---- .../io/impl/point_cloud_image_extractors.hpp | 14 ++++++------- io/include/pcl/io/pcd_grabber.h | 4 ++-- ml/include/pcl/ml/impl/kmeans.hpp | 10 +++++----- ml/src/kmeans.cpp | 10 +++++----- .../segmentation/impl/crf_segmentation.hpp | 6 +++--- .../segmentation/impl/unary_classifier.hpp | 6 +++--- test/io/test_io.cpp | 8 ++++---- tools/vfh_estimation.cpp | 2 +- .../pcl/visualization/impl/pcl_visualizer.hpp | 8 ++++---- .../impl/point_cloud_color_handlers.hpp | 20 +++++++++---------- .../impl/point_cloud_geometry_handlers.hpp | 12 +++++------ .../point_cloud_geometry_handlers.h | 6 +++--- 23 files changed, 86 insertions(+), 85 deletions(-) diff --git a/apps/src/pcd_select_object_plane.cpp b/apps/src/pcd_select_object_plane.cpp index 3ec5db140bc..4b29ecc466d 100644 --- a/apps/src/pcd_select_object_plane.cpp +++ b/apps/src/pcd_select_object_plane.cpp @@ -529,7 +529,7 @@ class ObjectSelection // If the dataset is organized, and has RGB data, create an image viewer std::vector fields; int rgba_index = -1; - rgba_index = getFieldIndex (*cloud_, "rgba", fields); + rgba_index = getFieldIndex ("rgba", fields); if (rgba_index >= 0) { diff --git a/common/include/pcl/common/impl/io.hpp b/common/include/pcl/common/impl/io.hpp index 3bf37ab871b..25320156304 100644 --- a/common/include/pcl/common/impl/io.hpp +++ b/common/include/pcl/common/impl/io.hpp @@ -65,22 +65,19 @@ template int pcl::getFieldIndex (const std::string &field_name, std::vector &fields) { - fields.clear (); - // Get the fields list - pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); - for (size_t d = 0; d < fields.size (); ++d) - if (fields[d].name == field_name) - return (static_cast(d)); - return (-1); + getFields (fields); + const auto result = std::find_if(fields.begin (), fields.end (), + [&field_name](const auto& field) { return field.name == field_name; }); + if (result == fields.end ()) + return -1; + return std::distance(fields.begin (), result); } ////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::getFields (const pcl::PointCloud &, std::vector &fields) { - fields.clear (); - // Get the fields list - pcl::for_each_type::type>(pcl::detail::FieldAdder(fields)); + getFields (fields); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index db177c686b0..c11c6e7c99f 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -71,7 +71,9 @@ namespace pcl * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains * \ingroup common */ - template inline int + template + [[deprecated("use getFieldIndex () instead")]] + inline int getFieldIndex (const pcl::PointCloud &cloud, const std::string &field_name, std::vector &fields); @@ -89,7 +91,9 @@ namespace pcl * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains * \ingroup common */ - template inline void + template + [[deprecated("use getFields () instead")]] + inline void getFields (const pcl::PointCloud &cloud, std::vector &fields); /** \brief Get the list of available fields (i.e., dimension/channel) diff --git a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp index 54f5b00e78a..66fedd7d599 100644 --- a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp @@ -46,7 +46,7 @@ loadHist (const boost::filesystem::path &path, vfh_model &vfh) vfh.second.resize (308); std::vector fields; - pcl::getFieldIndex (point, "vfh", fields); + pcl::getFieldIndex ("vfh", fields); for (size_t i = 0; i < fields[vfh_idx].count; ++i) { diff --git a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp index b47e4ee2254..e3284b4e8d5 100644 --- a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp @@ -49,7 +49,7 @@ loadHist (const boost::filesystem::path &path, vfh_model &vfh) vfh.second.resize (308); std::vector fields; - getFieldIndex (point, "vfh", fields); + pcl::getFieldIndex ("vfh", fields); for (size_t i = 0; i < fields[vfh_idx].count; ++i) { diff --git a/filters/include/pcl/filters/impl/approximate_voxel_grid.hpp b/filters/include/pcl/filters/impl/approximate_voxel_grid.hpp index 5105126d52a..358bb66f3d0 100644 --- a/filters/include/pcl/filters/impl/approximate_voxel_grid.hpp +++ b/filters/include/pcl/filters/impl/approximate_voxel_grid.hpp @@ -71,9 +71,9 @@ pcl::ApproximateVoxelGrid::applyFilter (PointCloud &output) // ---[ RGB special case std::vector fields; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); if (rgba_index >= 0) { rgba_index = fields[rgba_index].offset; diff --git a/filters/include/pcl/filters/impl/passthrough.hpp b/filters/include/pcl/filters/impl/passthrough.hpp index f800393389b..ef678f611a9 100644 --- a/filters/include/pcl/filters/impl/passthrough.hpp +++ b/filters/include/pcl/filters/impl/passthrough.hpp @@ -100,7 +100,7 @@ pcl::PassThrough::applyFilterIndices (std::vector &indices) { // Attempt to get the field name's index std::vector fields; - int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + int distance_idx = pcl::getFieldIndex (filter_field_name_, fields); if (distance_idx == -1) { PCL_WARN ("[pcl::%s::applyFilter] Unable to find field name in point type.\n", getClassName ().c_str ()); diff --git a/filters/include/pcl/filters/impl/voxel_grid.hpp b/filters/include/pcl/filters/impl/voxel_grid.hpp index e78fa4c91ac..efb8dd71026 100644 --- a/filters/include/pcl/filters/impl/voxel_grid.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid.hpp @@ -55,7 +55,7 @@ pcl::getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, // Get the fields list and the distance field index std::vector fields; - int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields); + int distance_idx = pcl::getFieldIndex (distance_field_name, fields); float distance_value; // If dense, no need to check for NaNs @@ -134,7 +134,7 @@ pcl::getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, // Get the fields list and the distance field index std::vector fields; - int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields); + int distance_idx = pcl::getFieldIndex (distance_field_name, fields); float distance_value; // If dense, no need to check for NaNs @@ -269,7 +269,7 @@ pcl::VoxelGrid::applyFilter (PointCloud &output) { // Get the distance field index std::vector fields; - int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + int distance_idx = pcl::getFieldIndex (filter_field_name_, fields); if (distance_idx == -1) PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx); diff --git a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp index 811434301e3..46ee9daa0fb 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp @@ -109,9 +109,9 @@ pcl::VoxelGridCovariance::applyFilter (PointCloud &output) // ---[ RGB special case std::vector fields; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); if (rgba_index >= 0) { rgba_index = fields[rgba_index].offset; @@ -123,7 +123,7 @@ pcl::VoxelGridCovariance::applyFilter (PointCloud &output) { // Get the distance field index std::vector fields; - int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + int distance_idx = pcl::getFieldIndex (filter_field_name_, fields); if (distance_idx == -1) PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx); diff --git a/filters/src/voxel_grid_label.cpp b/filters/src/voxel_grid_label.cpp index fcb8c6f6391..1a8bf080823 100644 --- a/filters/src/voxel_grid_label.cpp +++ b/filters/src/voxel_grid_label.cpp @@ -99,9 +99,9 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output) // ---[ RGB special case std::vector fields; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*input_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*input_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); if (rgba_index >= 0) { rgba_index = fields[rgba_index].offset; @@ -110,7 +110,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output) // ---[ Label special case int label_index = -1; - label_index = pcl::getFieldIndex (*input_, "label", fields); + label_index = pcl::getFieldIndex ("label", fields); std::vector index_vector; index_vector.reserve(input_->points.size()); @@ -120,7 +120,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output) { // Get the distance field index std::vector fields; - int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields); + int distance_idx = pcl::getFieldIndex (filter_field_name_, fields); if (distance_idx == -1) PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx); diff --git a/io/include/pcl/compression/impl/octree_pointcloud_compression.hpp b/io/include/pcl/compression/impl/octree_pointcloud_compression.hpp index bfb441841a0..f992a58b93d 100644 --- a/io/include/pcl/compression/impl/octree_pointcloud_compression.hpp +++ b/io/include/pcl/compression/impl/octree_pointcloud_compression.hpp @@ -74,10 +74,10 @@ namespace pcl cloud_with_color_ = false; std::vector fields; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*this->input_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) { - rgba_index = pcl::getFieldIndex (*this->input_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); } if (rgba_index >= 0) { @@ -190,9 +190,9 @@ namespace pcl cloud_with_color_ = false; std::vector fields; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*output_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*output_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); if (rgba_index >= 0) { point_color_offset_ = static_cast (fields[rgba_index].offset); diff --git a/io/include/pcl/io/impl/point_cloud_image_extractors.hpp b/io/include/pcl/io/impl/point_cloud_image_extractors.hpp index aa1a56929fb..98075701047 100644 --- a/io/include/pcl/io/impl/point_cloud_image_extractors.hpp +++ b/io/include/pcl/io/impl/point_cloud_image_extractors.hpp @@ -71,9 +71,9 @@ template bool pcl::io::PointCloudImageExtractorFromNormalField::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const { std::vector fields; - int field_x_idx = pcl::getFieldIndex (cloud, "normal_x", fields); - int field_y_idx = pcl::getFieldIndex (cloud, "normal_y", fields); - int field_z_idx = pcl::getFieldIndex (cloud, "normal_z", fields); + int field_x_idx = pcl::getFieldIndex ("normal_x", fields); + int field_y_idx = pcl::getFieldIndex ("normal_y", fields); + int field_z_idx = pcl::getFieldIndex ("normal_z", fields); if (field_x_idx == -1 || field_y_idx == -1 || field_z_idx == -1) return (false); const size_t offset_x = fields[field_x_idx].offset; @@ -107,10 +107,10 @@ template bool pcl::io::PointCloudImageExtractorFromRGBField::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const { std::vector fields; - int field_idx = pcl::getFieldIndex (cloud, "rgb", fields); + int field_idx = pcl::getFieldIndex ("rgb", fields); if (field_idx == -1) { - field_idx = pcl::getFieldIndex (cloud, "rgba", fields); + field_idx = pcl::getFieldIndex ("rgba", fields); if (field_idx == -1) return (false); } @@ -139,7 +139,7 @@ template bool pcl::io::PointCloudImageExtractorFromLabelField::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const { std::vector fields; - int field_idx = pcl::getFieldIndex (cloud, "label", fields); + int field_idx = pcl::getFieldIndex ("label", fields); if (field_idx == -1) return (false); const size_t offset = fields[field_idx].offset; @@ -244,7 +244,7 @@ template bool pcl::io::PointCloudImageExtractorWithScaling::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const { std::vector fields; - int field_idx = pcl::getFieldIndex (cloud, field_name_, fields); + int field_idx = pcl::getFieldIndex (field_name_, fields); if (field_idx == -1) return (false); const size_t offset = fields[field_idx].offset; diff --git a/io/include/pcl/io/pcd_grabber.h b/io/include/pcl/io/pcd_grabber.h index 25a4e51cc23..10acb870ae2 100644 --- a/io/include/pcl/io/pcd_grabber.h +++ b/io/include/pcl/io/pcd_grabber.h @@ -276,9 +276,9 @@ namespace pcl // ---[ RGB special case std::vector fields; - int rgba_index = pcl::getFieldIndex (*cloud, "rgb", fields); + int rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*cloud, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); if (rgba_index >= 0) { rgba_index = fields[rgba_index].offset; diff --git a/ml/include/pcl/ml/impl/kmeans.hpp b/ml/include/pcl/ml/impl/kmeans.hpp index 79449e4b78d..a868276f2f9 100644 --- a/ml/include/pcl/ml/impl/kmeans.hpp +++ b/ml/include/pcl/ml/impl/kmeans.hpp @@ -88,11 +88,11 @@ pcl::Kmeans::cluster (std::vector &clusters) int x_index = -1; int y_index = -1; int z_index = -1; - x_index = pcl::getFieldIndex (point, "x", fields); + x_index = pcl::getFieldIndex ("x", fields); if (y_index != -1) - y_index = pcl::getFieldIndex (point, "y", fields); + y_index = pcl::getFieldIndex ("y", fields); if (z_index != -1) - z_index = pcl::getFieldIndex (point, "z", fields); + z_index = pcl::getFieldIndex ("z", fields); if (x_index == -1 && y_index == -1 && z_index == -1) { @@ -135,7 +135,7 @@ pcl::Kmeans::cluster (std::vector &clusters) // if cluster field name is set, check if field name is valid else { - user_index = pcl::getFieldIndex (point, cluster_field_name_.c_str (), fields); + user_index = pcl::getFieldIndex (cluster_field_name_.c_str (), fields); if (user_index == -1) { @@ -150,7 +150,7 @@ pcl::Kmeans::cluster (std::vector &clusters) /* int xyz_index = -1; pcl::PointCloud point; - xyz_index = pcl::getFieldIndex (point, "r", fields); + xyz_index = pcl::getFieldIndex ("r", fields); if (xyz_index == -1 && strcmp (cluster_field_name_.c_str (), "") == 0) diff --git a/ml/src/kmeans.cpp b/ml/src/kmeans.cpp index 74dbc3b132a..7af149b818b 100644 --- a/ml/src/kmeans.cpp +++ b/ml/src/kmeans.cpp @@ -203,11 +203,11 @@ pcl::Kmeans::cluster (std::vector &clusters) int x_index = -1; int y_index = -1; int z_index = -1; - x_index = pcl::getFieldIndex (point, "x", fields); + x_index = pcl::getFieldIndex ("x", fields); if (y_index != -1) - y_index = pcl::getFieldIndex (point, "y", fields); + y_index = pcl::getFieldIndex ("y", fields); if (z_index != -1) - z_index = pcl::getFieldIndex (point, "z", fields); + z_index = pcl::getFieldIndex ("z", fields); if (x_index == -1 && y_index == -1 && z_index == -1) { @@ -253,7 +253,7 @@ pcl::Kmeans::cluster (std::vector &clusters) // if cluster field name is set, check if field name is valid else { - user_index = pcl::getFieldIndex (point, cluster_field_name_.c_str (), fields); + user_index = pcl::getFieldIndex (cluster_field_name_.c_str (), fields); if (user_index == -1) { @@ -268,7 +268,7 @@ pcl::Kmeans::cluster (std::vector &clusters) /* int xyz_index = -1; pcl::PointCloud point; - xyz_index = pcl::getFieldIndex (point, "r", fields); + xyz_index = pcl::getFieldIndex ("r", fields); if (xyz_index == -1 && strcmp (cluster_field_name_.c_str (), "") == 0) diff --git a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp index cd90ee2af97..45d11b3296c 100644 --- a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp @@ -250,9 +250,9 @@ pcl::CrfSegmentation::createDataVectorFromVoxelGrid () // check if we have color data bool color_data = false; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*input_cloud_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*input_cloud_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); if (rgba_index >= 0) { color_data = true; @@ -264,7 +264,7 @@ pcl::CrfSegmentation::createDataVectorFromVoxelGrid () // check if we have normal data bool normal_data = false; int normal_index = -1; - rgba_index = pcl::getFieldIndex (*input_cloud_, "normal_x", fields); + rgba_index = pcl::getFieldIndex ("normal_x", fields); if (rgba_index >= 0) { normal_data = true; diff --git a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp index 4dd3073d2d9..4b5cb223431 100644 --- a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp +++ b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp @@ -74,7 +74,7 @@ pcl::UnaryClassifier::setInputCloud (typename pcl::PointCloud::P std::vector fields; int label_index = -1; - label_index = pcl::getFieldIndex (point, "label", fields); + label_index = pcl::getFieldIndex ("label", fields); if (label_index != -1) label_field_ = true; @@ -137,7 +137,7 @@ pcl::UnaryClassifier::findClusters (typename pcl::PointCloud::Pt std::vector fields; int label_idx = -1; pcl::PointCloud point; - label_idx = pcl::getFieldIndex (point, "label", fields); + label_idx = pcl::getFieldIndex ("label", fields); if (label_idx != -1) { @@ -173,7 +173,7 @@ pcl::UnaryClassifier::getCloudWithLabel (typename pcl::PointCloud fields; int label_idx = -1; pcl::PointCloud point; - label_idx = pcl::getFieldIndex (point, "label", fields); + label_idx = pcl::getFieldIndex ("label", fields); if (label_idx != -1) { diff --git a/test/io/test_io.cpp b/test/io/test_io.cpp index 2b065666cc2..d0d1e9fb0bf 100644 --- a/test/io/test_io.cpp +++ b/test/io/test_io.cpp @@ -391,28 +391,28 @@ TEST (PCL, IO) std::vector fields; pcl::getFields (cloud, fields); EXPECT_EQ (fields.size (), size_t (4)); - int x_idx = pcl::getFieldIndex (cloud, "x", fields); + int x_idx = pcl::getFieldIndex ("x", fields); EXPECT_EQ (x_idx, 0); EXPECT_EQ (fields[x_idx].offset, uint32_t (0)); EXPECT_EQ (fields[x_idx].name, "x"); EXPECT_EQ (fields[x_idx].datatype, pcl::PCLPointField::FLOAT32); EXPECT_EQ (fields[x_idx].count, uint32_t (1)); - int y_idx = pcl::getFieldIndex (cloud, "y", fields); + int y_idx = pcl::getFieldIndex ("y", fields); EXPECT_EQ (y_idx, 1); EXPECT_EQ (fields[y_idx].offset, uint32_t (4)); EXPECT_EQ (fields[y_idx].name, "y"); EXPECT_EQ (fields[y_idx].datatype, pcl::PCLPointField::FLOAT32); EXPECT_EQ (fields[y_idx].count, uint32_t (1)); - int z_idx = pcl::getFieldIndex (cloud, "z", fields); + int z_idx = pcl::getFieldIndex ("z", fields); EXPECT_EQ (z_idx, 2); EXPECT_EQ (fields[z_idx].offset, uint32_t (8)); EXPECT_EQ (fields[z_idx].name, "z"); EXPECT_EQ (fields[z_idx].datatype, pcl::PCLPointField::FLOAT32); EXPECT_EQ (fields[z_idx].count, uint32_t (1)); - int intensity_idx = pcl::getFieldIndex (cloud, "intensity", fields); + int intensity_idx = pcl::getFieldIndex ("intensity", fields); EXPECT_EQ (intensity_idx, 3); EXPECT_EQ (fields[intensity_idx].offset, uint32_t (16)); // NOTE: intensity_idx.offset should be 12, but we are padding in PointXYZ (!) EXPECT_EQ (fields[intensity_idx].name, "intensity"); diff --git a/tools/vfh_estimation.cpp b/tools/vfh_estimation.cpp index 374a0cc900c..9ef12a9e226 100644 --- a/tools/vfh_estimation.cpp +++ b/tools/vfh_estimation.cpp @@ -68,7 +68,7 @@ loadCloud (const std::string &filename, PointCloud &cloud) // Check if the dataset has normals std::vector fields; - if (getFieldIndex (cloud, "normal_x", fields) == -1) + if (getFieldIndex ("normal_x", fields) == -1) { print_error ("The input dataset does not contain normal information!\n"); return (false); diff --git a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp index ae4004514ca..8b5a0e4ac22 100644 --- a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp +++ b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp @@ -1628,9 +1628,9 @@ pcl::visualization::PCLVisualizer::addPolygonMesh ( int rgb_idx = -1; std::vector fields; vtkSmartPointer colors; - rgb_idx = pcl::getFieldIndex (*cloud, "rgb", fields); + rgb_idx = pcl::getFieldIndex ("rgb", fields); if (rgb_idx == -1) - rgb_idx = pcl::getFieldIndex (*cloud, "rgba", fields); + rgb_idx = pcl::getFieldIndex ("rgba", fields); if (rgb_idx != -1) { colors = vtkSmartPointer::New (); @@ -1845,9 +1845,9 @@ pcl::visualization::PCLVisualizer::updatePolygonMesh ( return (false); int rgb_idx = -1; std::vector fields; - rgb_idx = pcl::getFieldIndex (*cloud, "rgb", fields); + rgb_idx = pcl::getFieldIndex ("rgb", fields); if (rgb_idx == -1) - rgb_idx = pcl::getFieldIndex (*cloud, "rgba", fields); + rgb_idx = pcl::getFieldIndex ("rgba", fields); if (rgb_idx != -1 && colors) { int j = 0; diff --git a/visualization/include/pcl/visualization/impl/point_cloud_color_handlers.hpp b/visualization/include/pcl/visualization/impl/point_cloud_color_handlers.hpp index 09a0c3c5d47..1bb58530163 100644 --- a/visualization/include/pcl/visualization/impl/point_cloud_color_handlers.hpp +++ b/visualization/include/pcl/visualization/impl/point_cloud_color_handlers.hpp @@ -111,7 +111,7 @@ pcl::visualization::PointCloudColorHandlerRGBField::setInputCloud ( { PointCloudColorHandler::setInputCloud (cloud); // Handle the 24-bit packed RGB values - field_idx_ = pcl::getFieldIndex (*cloud, "rgb", fields_); + field_idx_ = pcl::getFieldIndex ("rgb", fields_); if (field_idx_ != -1) { capable_ = true; @@ -119,7 +119,7 @@ pcl::visualization::PointCloudColorHandlerRGBField::setInputCloud ( } else { - field_idx_ = pcl::getFieldIndex (*cloud, "rgba", fields_); + field_idx_ = pcl::getFieldIndex ("rgba", fields_); if (field_idx_ != -1) capable_ = true; else @@ -137,9 +137,9 @@ pcl::visualization::PointCloudColorHandlerRGBField::getColor () const // Get the RGB field index std::vector fields; int rgba_index = -1; - rgba_index = pcl::getFieldIndex (*cloud_, "rgb", fields); + rgba_index = pcl::getFieldIndex ("rgb", fields); if (rgba_index == -1) - rgba_index = pcl::getFieldIndex (*cloud_, "rgba", fields); + rgba_index = pcl::getFieldIndex ("rgba", fields); int rgba_offset = fields[rgba_index].offset; @@ -197,7 +197,7 @@ pcl::visualization::PointCloudColorHandlerHSVField::PointCloudColorHandl pcl::visualization::PointCloudColorHandler::PointCloudColorHandler (cloud) { // Check for the presence of the "H" field - field_idx_ = pcl::getFieldIndex (*cloud, "h", fields_); + field_idx_ = pcl::getFieldIndex ("h", fields_); if (field_idx_ == -1) { capable_ = false; @@ -205,7 +205,7 @@ pcl::visualization::PointCloudColorHandlerHSVField::PointCloudColorHandl } // Check for the presence of the "S" field - s_field_idx_ = pcl::getFieldIndex (*cloud, "s", fields_); + s_field_idx_ = pcl::getFieldIndex ("s", fields_); if (s_field_idx_ == -1) { capable_ = false; @@ -213,7 +213,7 @@ pcl::visualization::PointCloudColorHandlerHSVField::PointCloudColorHandl } // Check for the presence of the "V" field - v_field_idx_ = pcl::getFieldIndex (*cloud, "v", fields_); + v_field_idx_ = pcl::getFieldIndex ("v", fields_); if (v_field_idx_ == -1) { capable_ = false; @@ -365,7 +365,7 @@ pcl::visualization::PointCloudColorHandlerGenericField::setInputCloud ( const PointCloudConstPtr &cloud) { PointCloudColorHandler::setInputCloud (cloud); - field_idx_ = pcl::getFieldIndex (*cloud, field_name_, fields_); + field_idx_ = pcl::getFieldIndex (field_name_, fields_); if (field_idx_ != -1) capable_ = true; else @@ -439,7 +439,7 @@ pcl::visualization::PointCloudColorHandlerRGBAField::setInputCloud ( { PointCloudColorHandler::setInputCloud (cloud); // Handle the 24-bit packed RGBA values - field_idx_ = pcl::getFieldIndex (*cloud, "rgba", fields_); + field_idx_ = pcl::getFieldIndex ("rgba", fields_); if (field_idx_ != -1) capable_ = true; else @@ -505,7 +505,7 @@ template void pcl::visualization::PointCloudColorHandlerLabelField::setInputCloud (const PointCloudConstPtr &cloud) { PointCloudColorHandler::setInputCloud (cloud); - field_idx_ = pcl::getFieldIndex (*cloud, "label", fields_); + field_idx_ = pcl::getFieldIndex ("label", fields_); if (field_idx_ != -1) { capable_ = true; diff --git a/visualization/include/pcl/visualization/impl/point_cloud_geometry_handlers.hpp b/visualization/include/pcl/visualization/impl/point_cloud_geometry_handlers.hpp index c61c61f1e2f..7b84fe5d104 100644 --- a/visualization/include/pcl/visualization/impl/point_cloud_geometry_handlers.hpp +++ b/visualization/include/pcl/visualization/impl/point_cloud_geometry_handlers.hpp @@ -46,13 +46,13 @@ template pcl::visualization::PointCloudGeometryHandlerXYZ::PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud) : pcl::visualization::PointCloudGeometryHandler::PointCloudGeometryHandler (cloud) { - field_x_idx_ = pcl::getFieldIndex (*cloud, "x", fields_); + field_x_idx_ = pcl::getFieldIndex ("x", fields_); if (field_x_idx_ == -1) return; - field_y_idx_ = pcl::getFieldIndex (*cloud, "y", fields_); + field_y_idx_ = pcl::getFieldIndex ("y", fields_); if (field_y_idx_ == -1) return; - field_z_idx_ = pcl::getFieldIndex (*cloud, "z", fields_); + field_z_idx_ = pcl::getFieldIndex ("z", fields_); if (field_z_idx_ == -1) return; capable_ = true; @@ -114,13 +114,13 @@ template pcl::visualization::PointCloudGeometryHandlerSurfaceNormal::PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud) : pcl::visualization::PointCloudGeometryHandler::PointCloudGeometryHandler (cloud) { - field_x_idx_ = pcl::getFieldIndex (*cloud, "normal_x", fields_); + field_x_idx_ = pcl::getFieldIndex ("normal_x", fields_); if (field_x_idx_ == -1) return; - field_y_idx_ = pcl::getFieldIndex (*cloud, "normal_y", fields_); + field_y_idx_ = pcl::getFieldIndex ("normal_y", fields_); if (field_y_idx_ == -1) return; - field_z_idx_ = pcl::getFieldIndex (*cloud, "normal_z", fields_); + field_z_idx_ = pcl::getFieldIndex ("normal_z", fields_); if (field_z_idx_ == -1) return; capable_ = true; diff --git a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h index 8f5f13124f3..2e41f8c5036 100644 --- a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h +++ b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h @@ -246,13 +246,13 @@ namespace pcl const std::string &z_field_name) : pcl::visualization::PointCloudGeometryHandler::PointCloudGeometryHandler (cloud) { - field_x_idx_ = pcl::getFieldIndex (*cloud, x_field_name, fields_); + field_x_idx_ = pcl::getFieldIndex (x_field_name, fields_); if (field_x_idx_ == -1) return; - field_y_idx_ = pcl::getFieldIndex (*cloud, y_field_name, fields_); + field_y_idx_ = pcl::getFieldIndex (y_field_name, fields_); if (field_y_idx_ == -1) return; - field_z_idx_ = pcl::getFieldIndex (*cloud, z_field_name, fields_); + field_z_idx_ = pcl::getFieldIndex (z_field_name, fields_); if (field_z_idx_ == -1) return; field_name_ = x_field_name + y_field_name + z_field_name;