Skip to content

Commit

Permalink
Removes deprecated usage of getFields(cloud, fields)
Browse files Browse the repository at this point in the history
  • Loading branch information
kunaltyagi committed Sep 27, 2019
1 parent 29f192a commit 9d13d25
Show file tree
Hide file tree
Showing 8 changed files with 18 additions and 28 deletions.
20 changes: 5 additions & 15 deletions filters/include/pcl/filters/impl/conditional_removal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,7 @@ pcl::FieldComparison<PointT>::FieldComparison (

// Get all fields
std::vector<pcl::PCLPointField> point_fields;
// Use a dummy cloud to get the field types in a clever way
PointCloud<PointT> dummyCloud;
pcl::getFields (dummyCloud, point_fields);
pcl::getFields<PointT> (point_fields);

// Find field_name
if (point_fields.empty ())
Expand Down Expand Up @@ -143,9 +141,7 @@ pcl::PackedRGBComparison<PointT>::PackedRGBComparison (
{
// get all the fields
std::vector<pcl::PCLPointField> point_fields;
// Use a dummy cloud to get the field types in a clever way
PointCloud<PointT> dummyCloud;
pcl::getFields (dummyCloud, point_fields);
pcl::getFields<PointT> (point_fields);

// Locate the "rgb" field
size_t d;
Expand Down Expand Up @@ -235,9 +231,7 @@ pcl::PackedHSIComparison<PointT>::PackedHSIComparison (
{
// Get all the fields
std::vector<pcl::PCLPointField> point_fields;
// Use a dummy cloud to get the field types in a clever way
PointCloud<PointT> dummyCloud;
pcl::getFields (dummyCloud, point_fields);
pcl::getFields<PointT> (point_fields);

// Locate the "rgb" field
size_t d;
Expand Down Expand Up @@ -384,9 +378,7 @@ pcl::TfQuadraticXYZComparison<PointT>::TfQuadraticXYZComparison () :
{
// get all the fields
std::vector<pcl::PCLPointField> point_fields;
// Use a dummy cloud to get the field types in a clever way
PointCloud<PointT> dummyCloud;
pcl::getFields (dummyCloud, point_fields);
pcl::getFields<PointT> (point_fields);

// Locate the "x" field
size_t dX;
Expand Down Expand Up @@ -449,9 +441,7 @@ pcl::TfQuadraticXYZComparison<PointT>::TfQuadraticXYZComparison (const pcl::Comp
{
// get all the fields
std::vector<pcl::PCLPointField> point_fields;
// Use a dummy cloud to get the field types in a clever way
PointCloud<PointT> dummyCloud;
pcl::getFields (dummyCloud, point_fields);
pcl::getFields<PointT> (point_fields);

// Locate the "x" field
size_t dX;
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/impl/random_sample.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ pcl::RandomSample<PointT>::applyFilter (PointCloud &output)
copyPointCloud (*input_, output);
// Get X, Y, Z fields
std::vector<pcl::PCLPointField> fields;
pcl::getFields (*input_, fields);
pcl::getFields<PointT> (fields);
std::vector<size_t> offsets;
for (const auto &field : fields)
{
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/impl/pcd_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ pcl::PCDWriter::generateHeader (const pcl::PointCloud<PointT> &cloud, const int
"\nFIELDS";

std::vector<pcl::PCLPointField> fields;
pcl::getFields (cloud, fields);
pcl::getFields<PointT> (fields);

std::stringstream field_names, field_types, field_sizes, field_counts;
for (const auto &field : fields)
Expand Down Expand Up @@ -146,7 +146,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
size_t fsize = 0;
size_t data_size = 0;
size_t nri = 0;
pcl::getFields (cloud, fields);
pcl::getFields<PointT> (fields);
// Compute the total size of the fields
for (const auto &field : fields)
{
Expand Down Expand Up @@ -278,7 +278,7 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name,
size_t fsize = 0;
size_t data_size = 0;
size_t nri = 0;
pcl::getFields (cloud, fields);
pcl::getFields<PointT> (fields);
std::vector<int> fields_sizes (fields.size ());
// Compute the total size of the fields
for (const auto &field : fields)
Expand Down Expand Up @@ -465,7 +465,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
fs.imbue (std::locale::classic ());

std::vector<pcl::PCLPointField> fields;
pcl::getFields (cloud, fields);
pcl::getFields<PointT> (fields);

// Write the header information
fs << generateHeader<PointT> (cloud) << "DATA ascii\n";
Expand Down Expand Up @@ -626,7 +626,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
size_t fsize = 0;
size_t data_size = 0;
size_t nri = 0;
pcl::getFields (cloud, fields);
pcl::getFields<PointT> (fields);
// Compute the total size of the fields
for (const auto &field : fields)
{
Expand Down Expand Up @@ -749,7 +749,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
fs.imbue (std::locale::classic ());

std::vector<pcl::PCLPointField> fields;
pcl::getFields (cloud, fields);
pcl::getFields<PointT> (fields);

// Write the header information
fs << generateHeader<PointT> (cloud, static_cast<int> (indices.size ())) << "DATA ascii\n";
Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/impl/sift_keypoint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ pcl::SIFTKeypoint<PointInT, PointOutT>::detectKeypoints (PointCloudOut &output)
}

// Check if the output has a "scale" field
scale_idx_ = pcl::getFieldIndex<PointOutT> (output, "scale", out_fields_);
scale_idx_ = pcl::getFieldIndex<PointOutT> ("scale", out_fields_);

// Make sure the output cloud is empty
output.points.clear ();
Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/impl/susan.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,7 +306,7 @@ pcl::SUSANKeypoint<PointInT, PointOutT, NormalT, IntensityT>::detectKeypoints (P
response->reserve (surface_->size ());

// Check if the output has a "label" field
label_idx_ = pcl::getFieldIndex<PointOutT> (output, "label", out_fields_);
label_idx_ = pcl::getFieldIndex<PointOutT> ("label", out_fields_);

const int input_size = static_cast<int> (input_->size ());
//#ifdef _OPENMP
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ namespace pcl
{
source_cloud_updated_ = true;
PCLBase<PointSource>::setInputCloud (cloud);
pcl::getFields (*cloud, input_fields_);
pcl::getFields<PointSource> (input_fields_);
}

/** \brief Get a pointer to the input point cloud dataset target. */
Expand Down
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/icp.h
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ namespace pcl
{
Registration<PointSource, PointTarget, Scalar>::setInputSource (cloud);
std::vector<pcl::PCLPointField> fields;
pcl::getFields (*cloud, fields);
pcl::getFields<PointSource> (fields);
source_has_normals_ = false;
for (const auto &field : fields)
{
Expand Down Expand Up @@ -213,7 +213,7 @@ namespace pcl
{
Registration<PointSource, PointTarget, Scalar>::setInputTarget (cloud);
std::vector<pcl::PCLPointField> fields;
pcl::getFields (*cloud, fields);
pcl::getFields<PointSource> (fields);
target_has_normals_ = false;
for (const auto &field : fields)
{
Expand Down
2 changes: 1 addition & 1 deletion test/io/test_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -389,7 +389,7 @@ TEST (PCL, IO)

// Test getFieldIndex
std::vector<pcl::PCLPointField> fields;
pcl::getFields (cloud, fields);
pcl::getFields<PointXYZI> (fields);
EXPECT_EQ (fields.size (), size_t (4));
int x_idx = pcl::getFieldIndex<PointXYZI> ("x", fields);
EXPECT_EQ (x_idx, 0);
Expand Down

0 comments on commit 9d13d25

Please sign in to comment.