Skip to content

Commit

Permalink
Deprecated getFieldIndex with first argument as cloud (#3365)
Browse files Browse the repository at this point in the history
Deprecate getFieldIndex() with first argument as cloud
  • Loading branch information
kunaltyagi authored and taketwo committed Sep 26, 2019
1 parent 8ab5ae4 commit 9684d29
Show file tree
Hide file tree
Showing 23 changed files with 86 additions and 85 deletions.
2 changes: 1 addition & 1 deletion apps/src/pcd_select_object_plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,7 +529,7 @@ class ObjectSelection
// If the dataset is organized, and has RGB data, create an image viewer
std::vector<pcl::PCLPointField> fields;
int rgba_index = -1;
rgba_index = getFieldIndex (*cloud_, "rgba", fields);
rgba_index = getFieldIndex<PointT> ("rgba", fields);

if (rgba_index >= 0)
{
Expand Down
17 changes: 7 additions & 10 deletions common/include/pcl/common/impl/io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,22 +65,19 @@ template <typename PointT> int
pcl::getFieldIndex (const std::string &field_name,
std::vector<pcl::PCLPointField> &fields)
{
fields.clear ();
// Get the fields list
pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
for (size_t d = 0; d < fields.size (); ++d)
if (fields[d].name == field_name)
return (static_cast<int>(d));
return (-1);
getFields<PointT> (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 <typename PointT> void
pcl::getFields (const pcl::PointCloud<PointT> &, std::vector<pcl::PCLPointField> &fields)
{
fields.clear ();
// Get the fields list
pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
getFields<PointT> (fields);
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
8 changes: 6 additions & 2 deletions common/include/pcl/common/io.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename PointT> inline int
template <typename PointT>
[[deprecated("use getFieldIndex<typename decltype(cloud)::PointType> () instead")]]
inline int
getFieldIndex (const pcl::PointCloud<PointT> &cloud, const std::string &field_name,
std::vector<pcl::PCLPointField> &fields);

Expand All @@ -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 <typename PointT> inline void
template <typename PointT>
[[deprecated("use getFields<typename decltype(cloud)::PointType> () instead")]]
inline void
getFields (const pcl::PointCloud<PointT> &cloud, std::vector<pcl::PCLPointField> &fields);

/** \brief Get the list of available fields (i.e., dimension/channel)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ loadHist (const boost::filesystem::path &path, vfh_model &vfh)
vfh.second.resize (308);

std::vector <pcl::PCLPointField> fields;
pcl::getFieldIndex (point, "vfh", fields);
pcl::getFieldIndex<pcl::VFHSignature308> ("vfh", fields);

for (size_t i = 0; i < fields[vfh_idx].count; ++i)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ loadHist (const boost::filesystem::path &path, vfh_model &vfh)
vfh.second.resize (308);

std::vector <pcl::PCLPointField> fields;
getFieldIndex (point, "vfh", fields);
pcl::getFieldIndex<pcl::VFHSignature308> ("vfh", fields);

for (size_t i = 0; i < fields[vfh_idx].count; ++i)
{
Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/impl/approximate_voxel_grid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,9 @@ pcl::ApproximateVoxelGrid<PointT>::applyFilter (PointCloud &output)
// ---[ RGB special case
std::vector<pcl::PCLPointField> fields;
int rgba_index = -1;
rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgb", fields);
if (rgba_index == -1)
rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgba", fields);
if (rgba_index >= 0)
{
rgba_index = fields[rgba_index].offset;
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/impl/passthrough.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ pcl::PassThrough<PointT>::applyFilterIndices (std::vector<int> &indices)
{
// Attempt to get the field name's index
std::vector<pcl::PCLPointField> fields;
int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
int distance_idx = pcl::getFieldIndex<PointT> (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 ());
Expand Down
6 changes: 3 additions & 3 deletions filters/include/pcl/filters/impl/voxel_grid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ pcl::getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,

// Get the fields list and the distance field index
std::vector<pcl::PCLPointField> fields;
int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields);
int distance_idx = pcl::getFieldIndex<PointT> (distance_field_name, fields);

float distance_value;
// If dense, no need to check for NaNs
Expand Down Expand Up @@ -134,7 +134,7 @@ pcl::getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,

// Get the fields list and the distance field index
std::vector<pcl::PCLPointField> fields;
int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields);
int distance_idx = pcl::getFieldIndex<PointT> (distance_field_name, fields);

float distance_value;
// If dense, no need to check for NaNs
Expand Down Expand Up @@ -269,7 +269,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
{
// Get the distance field index
std::vector<pcl::PCLPointField> fields;
int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
int distance_idx = pcl::getFieldIndex<PointT> (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);

Expand Down
6 changes: 3 additions & 3 deletions filters/include/pcl/filters/impl/voxel_grid_covariance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,9 @@ pcl::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
// ---[ RGB special case
std::vector<pcl::PCLPointField> fields;
int rgba_index = -1;
rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgb", fields);
if (rgba_index == -1)
rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgba", fields);
if (rgba_index >= 0)
{
rgba_index = fields[rgba_index].offset;
Expand All @@ -123,7 +123,7 @@ pcl::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
{
// Get the distance field index
std::vector<pcl::PCLPointField> fields;
int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
int distance_idx = pcl::getFieldIndex<PointT> (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);

Expand Down
8 changes: 4 additions & 4 deletions filters/src/voxel_grid_label.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,9 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
// ---[ RGB special case
std::vector<pcl::PCLPointField> fields;
int rgba_index = -1;
rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
rgba_index = pcl::getFieldIndex<PointXYZRGBL> ("rgb", fields);
if (rgba_index == -1)
rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointXYZRGBL> ("rgba", fields);
if (rgba_index >= 0)
{
rgba_index = fields[rgba_index].offset;
Expand All @@ -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<PointXYZRGBL> ("label", fields);

std::vector<cloud_point_index_idx> index_vector;
index_vector.reserve(input_->points.size());
Expand All @@ -120,7 +120,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
{
// Get the distance field index
std::vector<pcl::PCLPointField> fields;
int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
int distance_idx = pcl::getFieldIndex<PointXYZRGBL> (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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,10 +74,10 @@ namespace pcl
cloud_with_color_ = false;
std::vector<pcl::PCLPointField> fields;
int rgba_index = -1;
rgba_index = pcl::getFieldIndex (*this->input_, "rgb", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgb", fields);
if (rgba_index == -1)
{
rgba_index = pcl::getFieldIndex (*this->input_, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgba", fields);
}
if (rgba_index >= 0)
{
Expand Down Expand Up @@ -190,9 +190,9 @@ namespace pcl
cloud_with_color_ = false;
std::vector<pcl::PCLPointField> fields;
int rgba_index = -1;
rgba_index = pcl::getFieldIndex (*output_, "rgb", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgb", fields);
if (rgba_index == -1)
rgba_index = pcl::getFieldIndex (*output_, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgba", fields);
if (rgba_index >= 0)
{
point_color_offset_ = static_cast<unsigned char> (fields[rgba_index].offset);
Expand Down
14 changes: 7 additions & 7 deletions io/include/pcl/io/impl/point_cloud_image_extractors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,9 @@ template <typename PointT> bool
pcl::io::PointCloudImageExtractorFromNormalField<PointT>::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const
{
std::vector<pcl::PCLPointField> 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<PointT> ("normal_x", fields);
int field_y_idx = pcl::getFieldIndex<PointT> ("normal_y", fields);
int field_z_idx = pcl::getFieldIndex<PointT> ("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;
Expand Down Expand Up @@ -107,10 +107,10 @@ template <typename PointT> bool
pcl::io::PointCloudImageExtractorFromRGBField<PointT>::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const
{
std::vector<pcl::PCLPointField> fields;
int field_idx = pcl::getFieldIndex (cloud, "rgb", fields);
int field_idx = pcl::getFieldIndex<PointT> ("rgb", fields);
if (field_idx == -1)
{
field_idx = pcl::getFieldIndex (cloud, "rgba", fields);
field_idx = pcl::getFieldIndex<PointT> ("rgba", fields);
if (field_idx == -1)
return (false);
}
Expand Down Expand Up @@ -139,7 +139,7 @@ template <typename PointT> bool
pcl::io::PointCloudImageExtractorFromLabelField<PointT>::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const
{
std::vector<pcl::PCLPointField> fields;
int field_idx = pcl::getFieldIndex (cloud, "label", fields);
int field_idx = pcl::getFieldIndex<PointT> ("label", fields);
if (field_idx == -1)
return (false);
const size_t offset = fields[field_idx].offset;
Expand Down Expand Up @@ -244,7 +244,7 @@ template <typename PointT> bool
pcl::io::PointCloudImageExtractorWithScaling<PointT>::extractImpl (const PointCloud& cloud, pcl::PCLImage& img) const
{
std::vector<pcl::PCLPointField> fields;
int field_idx = pcl::getFieldIndex (cloud, field_name_, fields);
int field_idx = pcl::getFieldIndex<PointT> (field_name_, fields);
if (field_idx == -1)
return (false);
const size_t offset = fields[field_idx].offset;
Expand Down
4 changes: 2 additions & 2 deletions io/include/pcl/io/pcd_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -276,9 +276,9 @@ namespace pcl

// ---[ RGB special case
std::vector<pcl::PCLPointField> fields;
int rgba_index = pcl::getFieldIndex (*cloud, "rgb", fields);
int rgba_index = pcl::getFieldIndex<PointT> ("rgb", fields);
if (rgba_index == -1)
rgba_index = pcl::getFieldIndex (*cloud, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgba", fields);
if (rgba_index >= 0)
{
rgba_index = fields[rgba_index].offset;
Expand Down
10 changes: 5 additions & 5 deletions ml/include/pcl/ml/impl/kmeans.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,11 +88,11 @@ pcl::Kmeans<PointT>::cluster (std::vector<PointIndices> &clusters)
int x_index = -1;
int y_index = -1;
int z_index = -1;
x_index = pcl::getFieldIndex (point, "x", fields);
x_index = pcl::getFieldIndex<PointT> ("x", fields);
if (y_index != -1)
y_index = pcl::getFieldIndex (point, "y", fields);
y_index = pcl::getFieldIndex<PointT> ("y", fields);
if (z_index != -1)
z_index = pcl::getFieldIndex (point, "z", fields);
z_index = pcl::getFieldIndex<PointT> ("z", fields);

if (x_index == -1 && y_index == -1 && z_index == -1)
{
Expand Down Expand Up @@ -135,7 +135,7 @@ pcl::Kmeans<PointT>::cluster (std::vector<PointIndices> &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<PointT> (cluster_field_name_.c_str (), fields);

if (user_index == -1)
{
Expand All @@ -150,7 +150,7 @@ pcl::Kmeans<PointT>::cluster (std::vector<PointIndices> &clusters)
/*
int xyz_index = -1;
pcl::PointCloud <PointT> point;
xyz_index = pcl::getFieldIndex (point, "r", fields);
xyz_index = pcl::getFieldIndex<PointT> ("r", fields);
if (xyz_index == -1 && strcmp (cluster_field_name_.c_str (), "") == 0)
Expand Down
10 changes: 5 additions & 5 deletions ml/src/kmeans.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,11 +203,11 @@ pcl::Kmeans::cluster (std::vector<PointIndices> &clusters)
int x_index = -1;
int y_index = -1;
int z_index = -1;
x_index = pcl::getFieldIndex (point, "x", fields);
x_index = pcl::getFieldIndex<PointT> ("x", fields);
if (y_index != -1)
y_index = pcl::getFieldIndex (point, "y", fields);
y_index = pcl::getFieldIndex<PointT> ("y", fields);
if (z_index != -1)
z_index = pcl::getFieldIndex (point, "z", fields);
z_index = pcl::getFieldIndex<PointT> ("z", fields);
if (x_index == -1 && y_index == -1 && z_index == -1)
{
Expand Down Expand Up @@ -253,7 +253,7 @@ pcl::Kmeans::cluster (std::vector<PointIndices> &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<PointT> (cluster_field_name_.c_str (), fields);
if (user_index == -1)
{
Expand All @@ -268,7 +268,7 @@ pcl::Kmeans::cluster (std::vector<PointIndices> &clusters)
/*
int xyz_index = -1;
pcl::PointCloud <PointT> point;
xyz_index = pcl::getFieldIndex (point, "r", fields);
xyz_index = pcl::getFieldIndex<PointT> ("r", fields);
if (xyz_index == -1 && strcmp (cluster_field_name_.c_str (), "") == 0)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -250,9 +250,9 @@ pcl::CrfSegmentation<PointT>::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<PointT> ("rgb", fields);
if (rgba_index == -1)
rgba_index = pcl::getFieldIndex (*input_cloud_, "rgba", fields);
rgba_index = pcl::getFieldIndex<PointT> ("rgba", fields);
if (rgba_index >= 0)
{
color_data = true;
Expand All @@ -264,7 +264,7 @@ pcl::CrfSegmentation<PointT>::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<PointT> ("normal_x", fields);
if (rgba_index >= 0)
{
normal_data = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ pcl::UnaryClassifier<PointT>::setInputCloud (typename pcl::PointCloud<PointT>::P
std::vector<pcl::PCLPointField> fields;

int label_index = -1;
label_index = pcl::getFieldIndex (point, "label", fields);
label_index = pcl::getFieldIndex<PointT> ("label", fields);

if (label_index != -1)
label_field_ = true;
Expand Down Expand Up @@ -137,7 +137,7 @@ pcl::UnaryClassifier<PointT>::findClusters (typename pcl::PointCloud<PointT>::Pt
std::vector <pcl::PCLPointField> fields;
int label_idx = -1;
pcl::PointCloud <PointT> point;
label_idx = pcl::getFieldIndex (point, "label", fields);
label_idx = pcl::getFieldIndex<PointT> ("label", fields);

if (label_idx != -1)
{
Expand Down Expand Up @@ -173,7 +173,7 @@ pcl::UnaryClassifier<PointT>::getCloudWithLabel (typename pcl::PointCloud<PointT
std::vector <pcl::PCLPointField> fields;
int label_idx = -1;
pcl::PointCloud <PointT> point;
label_idx = pcl::getFieldIndex (point, "label", fields);
label_idx = pcl::getFieldIndex<PointT> ("label", fields);

if (label_idx != -1)
{
Expand Down
Loading

0 comments on commit 9684d29

Please sign in to comment.