Writing a new PCL class — Point Cloud Library 0.0 documentation (original) (raw)

Converting code to a PCL-like mentality/syntax for someone that comes in contact for the first time with our infrastructure might appear difficult, or raise certain questions.

This short guide is to serve as both a HowTo and a FAQ for writing new PCL classes, either from scratch, or by adapting old code.

Besides converting your code, this guide also explains some of the advantages of contributing your code to an already existing open source project. Here, we advocate for PCL, but you can certainly apply the same ideology to other similar projects.

Contents

Advantages: Why contribute?

The first question that someone might ask and we would like to answer is:

Why contribute to PCL, as in what are its advantages?

This question assumes you’ve already identified that the set of tools and libraries that PCL has to offer are useful for your project, so you have already become an user.

Because open source projects are mostly voluntary efforts, usually with developers geographically distributed around the world, it’s very common that the development process has a certain incremental, and iterative flavor. This means that:

In both cases, everyone has definitely encountered situations where either an algorithm/method that they need is missing, or an existing one is buggy. Therefore the next natural step is obvious:

change the existing code to fit your application/problem.

While we’re going to discuss how to do that in the next sections, we would still like to provide an answer for the first question that we raised, namely “why contribute?”.

In our opinion, there are many advantages. To quote Eric Raymond’s Linus’s Law: “given enough eyeballs, all bugs are shallow”. What this means is that by opening your code to the world, and allowing others to see it, the chances of it getting fixed and optimized are higher, especially in the presence of a dynamic community such as the one that PCL has.

In addition to the above, your contribution might enable, amongst many things:

For most of us, all of the above apply. For others, only some (your mileage might vary).

Example: a bilateral filter

To illustrate the code conversion process, we selected the following example: apply a bilateral filter over intensity data from a given input point cloud, and save the results to disk.

1 #include <pcl/point_types.h> 2 #include <pcl/io/pcd_io.h> 3 #include <pcl/kdtree/kdtree_flann.h> 4 5 typedef pcl::PointXYZI PointT; 6 7 float 8 G (float x, float sigma) 9 { 10 return std::exp (- (xx)/(2sigma*sigma)); 11 } 12 13 int 14 main (int argc, char *argv[]) 15 { 16 std::string incloudfile = argv[1]; 17 std::string outcloudfile = argv[2]; 18 float sigma_s = atof (argv[3]); 19 float sigma_r = atof (argv[4]); 20 21 // Load cloud 22 pcl::PointCloud::Ptr cloud (new pcl::PointCloud); 23 pcl::io::loadPCDFile (incloudfile.c_str (), *cloud); 24 int pnumber = (int)cloud->size (); 25 26 // Output Cloud = Input Cloud 27 pcl::PointCloud outcloud = *cloud; 28 29 // Set up KDTree 30 pcl::KdTreeFLANN::Ptr tree (new pcl::KdTreeFLANN); 31 tree->setInputCloud (cloud); 32 33 // Neighbors containers 34 std::vector k_indices; 35 std::vector k_distances; 36 37 // Main Loop 38 for (int point_id = 0; point_id < pnumber; ++point_id) 39 { 40 float BF = 0; 41 float W = 0; 42 43 tree->radiusSearch (point_id, 2 * sigma_s, k_indices, k_distances); 44 45 // For each neighbor 46 for (std::size_t n_id = 0; n_id < k_indices.size (); ++n_id) 47 { 48 float id = k_indices.at (n_id); 49 float dist = sqrt (k_distances.at (n_id)); 50 float intensity_dist = std::abs ((*cloud)[point_id].intensity - (*cloud)[id].intensity); 51 52 float w_a = G (dist, sigma_s); 53 float w_b = G (intensity_dist, sigma_r); 54 float weight = w_a * w_b; 55 56 BF += weight * (*cloud)[id].intensity; 57 W += weight; 58 } 59 60 outcloud[point_id].intensity = BF / W; 61 } 62 63 // Save filtered output 64 pcl::io::savePCDFile (outcloudfile.c_str (), outcloud); 65 return (0); 66 }

The presented code snippet contains:

Our goal here is to convert the algorithm given into an useful PCL class so that it can be reused elsewhere.

Setting up the structure

Note

If you’re not familiar with the PCL file structure already, please go ahead and read the PCL C++ Programming Style Guide to familiarize yourself with the concepts.

There’re two different ways we could set up the structure: i) set up the code separately, as a standalone PCL class, but outside of the PCL code tree; or ii) set up the files directly in the PCL code tree. Since our assumption is that the end result will be contributed back to PCL, it’s best to concentrate on the latter, also because it is a bit more complex (i.e., it involves a few additional steps). You can obviously repeat these steps with the former case as well, with the exception that you don’t need the files copied in the PCL tree, nor you need the fancier cmake logic.

Assuming that we want the new algorithm to be part of the PCL Filtering library, we will begin by creating 3 different files under filters:

We also need a name for our new class. Let’s call it BilateralFilter.

bilateral.h

As previously mentioned, the bilateral.h header file will contain all the definitions pertinent to the BilateralFilter class. Here’s a minimal skeleton:

1 #pragma once 2 3 #include <pcl/filters/filter.h> 4 5 namespace pcl 6 { 7 template 8 class BilateralFilter : public Filter 9 { 10 }; 11 }

bilateral.hpp

While we’re at it, let’s set up two skeleton bilateral.hpp and_bilateral.cpp_ files as well. First, bilateral.hpp:

1 #pragma once 2 3 #include <pcl/filters/bilateral.h>

This should be straightforward. We haven’t declared any methods forBilateralFilter yet, therefore there is no implementation.

bilateral.cpp

Let’s write bilateral.cpp too:

1 #include <pcl/filters/bilateral.h> 2 #include <pcl/filters/impl/bilateral.hpp>

Because we are writing templated code in PCL (1.x) where the template parameter is a point type (see Adding your own custom PointT type), we want to explicitly instantiate the most common use cases in bilateral.cpp, so that users don’t have to spend extra cycles when compiling code that uses ourBilateralFilter. To do this, we need to access both the header (bilateral.h) and the implementations (bilateral.hpp).

CMakeLists.txt

Let’s add all the files to the PCL Filtering CMakeLists.txt file, so we can enable the build.

1 # Find "set (srcs", and add a new entry there, e.g., 2 set (srcs 3 src/conditional_removal.cpp 4 # ... 5 src/bilateral.cpp 6 ) 7 8 # Find "set (incs", and add a new entry there, e.g., 9 set (incs 10 include pcl/${SUBSYS_NAME}/conditional_removal.h 11 # ... 12 include pcl/${SUBSYS_NAME}/bilateral.h 13 ) 14 15 # Find "set (impl_incs", and add a new entry there, e.g., 16 set (impl_incs 17 include/pcl/${SUBSYS_NAME}/impl/conditional_removal.hpp 18 # ... 19 include/pcl/${SUBSYS_NAME}/impl/bilateral.hpp 20 )

Filling in the class structure

If you correctly edited all the files above, recompiling PCL using the new filter classes in place should work without problems. In this section, we’ll begin filling in the actual code in each file. Let’s start with the_bilateral.cpp_ file, as its content is the shortest.

bilateral.cpp

As previously mentioned, we’re going to explicitly instantiate and_precompile_ a number of templated specializations for the BilateralFilterclass. While this might lead to an increased compilation time for the PCL Filtering library, it will save users the pain of processing and compiling the templates on their end, when they use the class in code they write. The simplest possible way to do this would be to declare each instance that we want to precompile by hand in the bilateral.cpp file as follows:

1 #include <pcl/point_types.h> 2 #include <pcl/filters/bilateral.h> 3 #include <pcl/filters/impl/bilateral.hpp> 4 5 template class PCL_EXPORTS pcl::BilateralFilterpcl::PointXYZ; 6 template class PCL_EXPORTS pcl::BilateralFilterpcl::PointXYZI; 7 template class PCL_EXPORTS pcl::BilateralFilterpcl::PointXYZRGB; 8 // ...

However, this becomes cumbersome really fast, as the number of point types PCL supports grows. Maintaining this list up to date in multiple files in PCL is also painful. Therefore, we are going to use a special macro calledPCL_INSTANTIATE and change the above code as follows:

1 #include <pcl/point_types.h> 2 #include <pcl/impl/instantiate.hpp> 3 #include <pcl/filters/bilateral.h> 4 #include <pcl/filters/impl/bilateral.hpp> 5 6 PCL_INSTANTIATE(BilateralFilter, PCL_XYZ_POINT_TYPES);

This example, will instantiate a BilateralFilter for all XYZ point types defined in the point_types.h file (seePCL_XYZ_POINT_TYPES for more information).

By looking closer at the code presented in Example: a bilateral filter, we notice constructs such as (*cloud)[point_id].intensity. This indicates that our filter expects the presence of an intensity field in the point type. Because of this, using PCL_XYZ_POINT_TYPES won’t work, as not all the types defined there have intensity data present. In fact, it’s easy to notice that only two of the types contain intensity, namely:PointXYZI andPointXYZINormal. We therefore replacePCL_XYZ_POINT_TYPES and the final bilateral.cpp file becomes:

1 #include <pcl/point_types.h> 2 #include <pcl/impl/instantiate.hpp> 3 #include <pcl/filters/bilateral.h> 4 #include <pcl/filters/impl/bilateral.hpp> 5 6 PCL_INSTANTIATE(BilateralFilter, (pcl::PointXYZI)(pcl::PointXYZINormal));

Note that at this point we haven’t declared the PCL_INSTANTIATE template forBilateralFilter, nor did we actually implement the pure virtual functions in the abstract class pcl::Filter so attempting to compile the code will result in errors like:

filters/src/bilateral.cpp:6:32: error: expected constructor, destructor, or type conversion before ‘(’ token

bilateral.h

We begin filling the BilateralFilter class by first declaring the constructor, and its member variables. Because the bilateral filtering algorithm has two parameters, we will store these as class members, and implement setters and getters for them, to be compatible with the PCL 1.x API paradigms.

1 ... 2 namespace pcl 3 { 4 template 5 class BilateralFilter : public Filter 6 { 7 public: 8 BilateralFilter () : sigma_s_ (0), 9 sigma_r_ (std::numeric_limits::max ()) 10 { 11 } 12 13 void 14 setSigmaS (const double sigma_s) 15 { 16 sigma_s_ = sigma_s; 17 } 18 19 double 20 getSigmaS () const 21 { 22 return (sigma_s_); 23 } 24 25 void 26 setSigmaR (const double sigma_r) 27 { 28 sigma_r_ = sigma_r; 29 } 30 31 double 32 getSigmaR () const 33 { 34 return (sigma_r_); 35 } 36 37 private: 38 double sigma_s_; 39 double sigma_r_; 40 }; 41 } 42 43 #endif // PCL_FILTERS_BILATERAL_H_

Nothing out of the ordinary so far, except maybe lines 8-9, where we gave some default values to the two parameters. Because our class inherits frompcl::Filter, and that inherits frompcl::PCLBase, we can make use of thesetInputCloud method to pass the input data to our algorithm (stored as input_). We therefore add an using declaration as follows:

1 ... 2 template 3 class BilateralFilter : public Filter 4 { 5 using Filter::input_; 6 public: 7 BilateralFilter () : sigma_s_ (0), 8 ...

This will make sure that our class has access to the member variable input_without typing the entire construct. Next, we observe that each class that inherits from pcl::Filter must inherit aapplyFilter method. We therefore define:

1 ... 2 using Filter::input_; 3 typedef typename Filter::PointCloud PointCloud; 4 5 public: 6 BilateralFilter () : sigma_s_ (0), 7 sigma_r_ (std::numeric_limits::max ()) 8 { 9 } 10 11 void 12 applyFilter (PointCloud &output); 13 ...

The implementation of applyFilter will be given in the bilateral.hpp file later. Line 3 constructs a typedef so that we can use the type PointCloudwithout typing the entire construct.

Looking at the original code from section Example: a bilateral filter, we notice that the algorithm consists of applying the same operation to every point in the cloud. To keep the applyFilter call clean, we therefore define method called computePointWeight whose implementation will contain the corpus defined in between lines 45-58:

1 ... 2 void 3 applyFilter (PointCloud &output); 4 5 double 6 computePointWeight (const int pid, const std::vector &indices, const std::vector &distances); 7 ...

In addition, we notice that lines 29-31 and 43 from sectionExample: a bilateral filter construct a KdTreestructure for obtaining the nearest neighbors for a given point. We therefore add:

1 #include <pcl/kdtree/kdtree.h> 2 ... 3 using Filter::input_; 4 typedef typename Filter::PointCloud PointCloud; 5 typedef typename pcl::KdTree::Ptr KdTreePtr; 6 7 public: 8 ... 9 10 void 11 setSearchMethod (const KdTreePtr &tree) 12 { 13 tree_ = tree; 14 } 15 16 private: 17 ... 18 KdTreePtr tree_; 19 ...

Finally, we would like to add the kernel method (G (float x, float sigma)) inline so that we speed up the computation of the filter. Because the method is only useful within the context of the algorithm, we will make it private. The header file becomes:

1 #pragma once 2 3 #include <pcl/filters/filter.h> 4 #include <pcl/kdtree/kdtree.h> 5 6 namespace pcl 7 { 8 template 9 class BilateralFilter : public Filter 10 { 11 using Filter::input_; 12 typedef typename Filter::PointCloud PointCloud; 13 typedef typename pcl::KdTree::Ptr KdTreePtr; 14 15 public: 16 BilateralFilter () : sigma_s_ (0), 17 sigma_r_ (std::numeric_limits::max ()) 18 { 19 } 20 21 22 void 23 applyFilter (PointCloud &output); 24 25 double 26 computePointWeight (const int pid, const std::vector &indices, const std::vector &distances); 27 28 void 29 setSigmaS (const double sigma_s) 30 { 31 sigma_s_ = sigma_s; 32 } 33 34 double 35 getSigmaS () const 36 { 37 return (sigma_s_); 38 } 39 40 void 41 setSigmaR (const double sigma_r) 42 { 43 sigma_r_ = sigma_r; 44 } 45 46 double 47 getSigmaR () const 48 { 49 return (sigma_r_); 50 } 51 52 void 53 setSearchMethod (const KdTreePtr &tree) 54 { 55 tree_ = tree; 56 } 57 58 59 private: 60 61 inline double 62 kernel (double x, double sigma) 63 { 64 return (std::exp (- (xx)/(2sigma*sigma))); 65 } 66 67 double sigma_s_; 68 double sigma_r_; 69 KdTreePtr tree_; 70 }; 71 }

bilateral.hpp

There’re two methods that we need to implement here, namely applyFilter andcomputePointWeight.

1 template double 2 pcl::BilateralFilter::computePointWeight (const int pid, 3 const std::vector &indices, 4 const std::vector &distances) 5 { 6 double BF = 0, W = 0; 7 8 // For each neighbor 9 for (std::size_t n_id = 0; n_id < indices.size (); ++n_id) 10 { 11 double id = indices[n_id]; 12 double dist = std::sqrt (distances[n_id]); 13 double intensity_dist = std::abs ((*input_)[pid].intensity - (*input_)[id].intensity); 14 15 double weight = kernel (dist, sigma_s_) * kernel (intensity_dist, sigma_r_); 16 17 BF += weight * (*input_)[id].intensity; 18 W += weight; 19 } 20 return (BF / W); 21 } 22 23 template void 24 pcl::BilateralFilter::applyFilter (PointCloud &output) 25 { 26 tree_->setInputCloud (input_); 27 28 std::vector k_indices; 29 std::vector k_distances; 30 31 output = *input_; 32 33 for (std::size_t point_id = 0; point_id < input_->size (); ++point_id) 34 { 35 tree_->radiusSearch (point_id, sigma_s_ * 2, k_indices, k_distances); 36 37 output[point_id].intensity = computePointWeight (point_id, k_indices, k_distances); 38 } 39 40 }

The computePointWeight method should be straightforward as it’s almost identical to lines 45-58 from section Example: a bilateral filter. We basically pass in a point index that we want to compute the intensity weight for, and a set of neighboring points with distances.

In applyFilter, we first set the input data in the tree, copy all the input data into the output, and then proceed at computing the new weighted point intensities.

Looking back at Filling in the class structure, it’s now time to declare the PCL_INSTANTIATEentry for the class:

1 #pragma once 2 3 #include <pcl/filters/bilateral.h> 4 5 ... 6 7 #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter;

One additional thing that we can do is error checking on:

For the former, we’re going to check the value of sigma_s_, which was set to a default of 0, and has a critical importance for the behavior of the algorithm (it basically defines the size of the support region). Therefore, if at the execution of the code, its value is still 0, we will print an error using thePCL_ERROR macro, and return.

In the case of the search method, we can either do the same, or be clever and provide a default option for the user. The best default options are:

1 #include <pcl/kdtree/kdtree_flann.h> 2 #include <pcl/kdtree/organized_data.h> 3 4 ... 5 template void 6 pcl::BilateralFilter::applyFilter (PointCloud &output) 7 { 8 if (sigma_s_ == 0) 9 { 10 PCL_ERROR ("[pcl::BilateralFilter::applyFilter] Need a sigma_s value given before continuing.\n"); 11 return; 12 } 13 if (!tree_) 14 { 15 if (input_->isOrganized ()) 16 tree_.reset (new pcl::OrganizedNeighbor ()); 17 else 18 tree_.reset (new pcl::KdTreeFLANN (false)); 19 } 20 tree_->setInputCloud (input_); 21 ...

The implementation file header thus becomes:

1 #pragma once 2 3 #include <pcl/filters/bilateral.h> 4 #include <pcl/kdtree/kdtree_flann.h> 5 #include <pcl/kdtree/organized_data.h> 6 7 template double 8 pcl::BilateralFilter::computePointWeight (const int pid, 9 const std::vector &indices, 10 const std::vector &distances) 11 { 12 double BF = 0, W = 0; 13 14 // For each neighbor 15 for (std::size_t n_id = 0; n_id < indices.size (); ++n_id) 16 { 17 double id = indices[n_id]; 18 double dist = std::sqrt (distances[n_id]); 19 double intensity_dist = std::abs ((*input_)[pid].intensity - (*input_)[id].intensity); 20 21 double weight = kernel (dist, sigma_s_) * kernel (intensity_dist, sigma_r_); 22 23 BF += weight * (*input_)[id].intensity; 24 W += weight; 25 } 26 return (BF / W); 27 } 28 29 template void 30 pcl::BilateralFilter::applyFilter (PointCloud &output) 31 { 32 if (sigma_s_ == 0) 33 { 34 PCL_ERROR ("[pcl::BilateralFilter::applyFilter] Need a sigma_s value given before continuing.\n"); 35 return; 36 } 37 if (!tree_) 38 { 39 if (input_->isOrganized ()) 40 tree_.reset (new pcl::OrganizedNeighbor ()); 41 else 42 tree_.reset (new pcl::KdTreeFLANN (false)); 43 } 44 tree_->setInputCloud (input_); 45 46 std::vector k_indices; 47 std::vector k_distances; 48 49 output = *input_; 50 51 for (std::size_t point_id = 0; point_id < input_->size (); ++point_id) 52 { 53 tree_->radiusSearch (point_id, sigma_s_ * 2, k_indices, k_distances); 54 55 output[point_id].intensity = computePointWeight (point_id, k_indices, k_distances); 56 } 57 } 58 59 #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter;

Taking advantage of other PCL concepts

Point indices

The standard way of passing point cloud data into PCL algorithms is viasetInputCloud calls. In addition, PCL also defines a way to define a region of interest / list of point indices that the algorithm should operate on, rather than the entire cloud, viasetIndices.

All classes inheriting from PCLBase exhibit the following behavior: in case no set of indices is given by the user, a fake one is created once and used for the duration of the algorithm. This means that we could easily change the implementation code above to operate on a _<cloud, indices>_tuple, which has the added advantage that if the user does pass a set of indices, only those will be used, and if not, the entire cloud will be used.

The new bilateral.hpp class thus becomes:

1 #include <pcl/kdtree/kdtree_flann.h> 2 #include <pcl/kdtree/organized_data.h> 3 4 ... 5 template void 6 pcl::BilateralFilter::applyFilter (PointCloud &output) 7 { 8 if (sigma_s_ == 0) 9 { 10 PCL_ERROR ("[pcl::BilateralFilter::applyFilter] Need a sigma_s value given before continuing.\n"); 11 return; 12 } 13 if (!tree_) 14 { 15 if (input_->isOrganized ()) 16 tree_.reset (new pcl::OrganizedNeighbor ()); 17 else 18 tree_.reset (new pcl::KdTreeFLANN (false)); 19 } 20 tree_->setInputCloud (input_); 21 ...

The implementation file header thus becomes:

1 #pragma once 2 3 #include <pcl/filters/bilateral.h> 4 #include <pcl/kdtree/kdtree_flann.h> 5 #include <pcl/kdtree/organized_data.h> 6 7 template double 8 pcl::BilateralFilter::computePointWeight (const int pid, 9 const std::vector &indices, 10 const std::vector &distances) 11 { 12 double BF = 0, W = 0; 13 14 // For each neighbor 15 for (std::size_t n_id = 0; n_id < indices.size (); ++n_id) 16 { 17 double id = indices[n_id]; 18 double dist = std::sqrt (distances[n_id]); 19 double intensity_dist = std::abs ((*input_)[pid].intensity - (*input_)[id].intensity); 20 21 double weight = kernel (dist, sigma_s_) * kernel (intensity_dist, sigma_r_); 22 23 BF += weight * (*input_)[id].intensity; 24 W += weight; 25 } 26 return (BF / W); 27 } 28 29 template void 30 pcl::BilateralFilter::applyFilter (PointCloud &output) 31 { 32 if (sigma_s_ == 0) 33 { 34 PCL_ERROR ("[pcl::BilateralFilter::applyFilter] Need a sigma_s value given before continuing.\n"); 35 return; 36 } 37 if (!tree_) 38 { 39 if (input_->isOrganized ()) 40 tree_.reset (new pcl::OrganizedNeighbor ()); 41 else 42 tree_.reset (new pcl::KdTreeFLANN (false)); 43 } 44 tree_->setInputCloud (input_); 45 46 std::vector k_indices; 47 std::vector k_distances; 48 49 output = *input_; 50 51 for (std::size_t i = 0; i < indices_->size (); ++i) 52 { 53 tree_->radiusSearch ((*indices_)[i], sigma_s_ * 2, k_indices, k_distances); 54 55 output[(*indices_)[i]].intensity = computePointWeight ((*indices_)[i], k_indices, k_distances); 56 } 57 } 58 59 #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter;

To make indices_ work without typing the full construct, we need to add a new line to bilateral.h that specifies the class where indices_ is declared:

1 ... 2 template 3 class BilateralFilter : public Filter 4 { 5 using Filter::input_; 6 using Filter::indices_; 7 public: 8 BilateralFilter () : sigma_s_ (0), 9 ...

Licenses

It is advised that each file contains a license that describes the author of the code. This is very useful for our users that need to understand what sort of restrictions are they bound to when using the code. PCL is 100% BSD licensed, and we insert the corpus of the license as a C++ comment in the file, as follows:

1/* 2* SPDX-License-Identifier: BSD-3-Clause 3* 4* Point Cloud Library (PCL) - www.pointclouds.org 5* Copyright (c) 2014-, Open Perception Inc. 6* 7* All rights reserved 8*/

An additional line can be inserted if additional copyright is needed (or the original copyright can be changed):

1 * Copyright (c) XXX, respective authors.

Proper naming

We wrote the tutorial so far by using silly named setters and getters in our example, like setSigmaS or setSigmaR. In reality, we would like to use a better naming scheme, that actually represents what the parameter is doing. In a final version of the code we could therefore rename the setters and getters to set/getHalfSize and set/getStdDev or something similar.

Testing the new class

Testing the new class is easy. We’ll take the first code snippet example as shown above, strip the algorithm, and make it use the pcl::BilateralFilterclass instead:

1 #include <pcl/point_types.h> 2 #include <pcl/io/pcd_io.h> 3 #include <pcl/kdtree/kdtree_flann.h> 4 #include <pcl/filters/bilateral.h> 5 6 typedef pcl::PointXYZI PointT; 7 8 int 9 main (int argc, char *argv[]) 10 { 11 std::string incloudfile = argv[1]; 12 std::string outcloudfile = argv[2]; 13 float sigma_s = atof (argv[3]); 14 float sigma_r = atof (argv[4]); 15 16 // Load cloud 17 pcl::PointCloud::Ptr cloud (new pcl::PointCloud); 18 pcl::io::loadPCDFile (incloudfile.c_str (), *cloud); 19 20 pcl::PointCloud outcloud; 21 22 // Set up KDTree 23 pcl::KdTreeFLANN::Ptr tree (new pcl::KdTreeFLANN); 24 25 pcl::BilateralFilter bf; 26 bf.setInputCloud (cloud); 27 bf.setSearchMethod (tree); 28 bf.setHalfSize (sigma_s); 29 bf.setStdDev (sigma_r); 30 bf.filter (outcloud); 31 32 // Save filtered output 33 pcl::io::savePCDFile (outcloudfile.c_str (), outcloud); 34 return (0); 35 }