35 #define BOOST_PARAMETER_MAX_ARITY 7 
   38 #include <geometry_msgs/PoseStamped.h> 
   39 #include <geometry_msgs/PointStamped.h> 
   42 #include <pcl/search/kdtree.h>   
   49     pcl::PointCloud<pcl::PointXYZRGB>::Ptr 
cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   50     pcl::PointCloud<pcl::PointXYZRGB>::Ptr result_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   53     std::vector<int> indices;
 
   54     cloud->is_dense = 
false;
 
   55     pcl::removeNaNFromPointCloud(*
cloud, *
cloud, indices);
 
   57     pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGB> smoother;
 
   60 #if PCL_VERSION_COMPARE (<, 1, 9, 0)  // https://github.com/PointCloudLibrary/pcl/blob/cc08f815a9a5f2a1d3f897fb2bc9d541635792c9/CHANGES.md?plain=1#L1633 
   66     typename pcl::search::KdTree<pcl::PointXYZRGB>::Ptr 
tree (
new typename pcl::search::KdTree<pcl::PointXYZRGB> ());
 
   67     smoother.setSearchMethod (
tree);
 
   68     smoother.setInputCloud (
cloud);
 
   69     smoother.process (*result_cloud);
 
   71     sensor_msgs::PointCloud2 pointcloud2;
 
   73     pointcloud2.header.frame_id = 
input->header.frame_id;
 
   74     pointcloud2.header.stamp = 
input->header.stamp;
 
  100     DiagnosticNodelet::onInit();
 
  106     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
 
  107     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  109     srv_->setCallback(
f);
 
  110     pub_ =advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output", 1);