moving_least_square_smoothing_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #define BOOST_PARAMETER_MAX_ARITY 7
37 
38 #include <geometry_msgs/PoseStamped.h>
39 #include <geometry_msgs/PointStamped.h>
40 
42 
43 namespace jsk_pcl_ros
44 {
45  void MovingLeastSquareSmoothing::smooth(const sensor_msgs::PointCloud2ConstPtr& input)
46  {
47  boost::mutex::scoped_lock lock(mutex_);
48  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
49  pcl::PointCloud<pcl::PointXYZRGB>::Ptr result_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
50  pcl::fromROSMsg(*input, *cloud);
51 
52  std::vector<int> indices;
53  cloud->is_dense = false;
54  pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
55 
56  pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGB> smoother;
57  smoother.setSearchRadius (search_radius_);
58  if (gauss_param_set_) smoother.setSqrGaussParam (gauss_param_set_);
59  smoother.setPolynomialFit (use_polynomial_fit_);
60  smoother.setPolynomialOrder (polynomial_order_);
61  smoother.setComputeNormals (calc_normal_);
62 
63  typename pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new typename pcl::search::KdTree<pcl::PointXYZRGB> ());
64  smoother.setSearchMethod (tree);
65  smoother.setInputCloud (cloud);
66  smoother.process (*result_cloud);
67 
68  sensor_msgs::PointCloud2 pointcloud2;
69  pcl::toROSMsg(*result_cloud, pointcloud2);
70  pointcloud2.header.frame_id = input->header.frame_id;
71  pointcloud2.header.stamp = input->header.stamp;
72  pub_.publish(pointcloud2);
73  }
74 
76  {
77  sub_input_ = pnh_->subscribe("input", 1, &MovingLeastSquareSmoothing::smooth, this);
78  }
79 
81  {
83  }
84 
85  void MovingLeastSquareSmoothing::configCallback(Config &config, uint32_t level)
86  {
87  boost::mutex::scoped_lock lock(mutex_);
88  search_radius_ = config.search_radius;
89  gauss_param_set_ = config.gauss_param_set;
90  use_polynomial_fit_ = config.use_polynomial_fit;
91  polynomial_order_ = config.polynomial_order;
92  calc_normal_ = config.calc_normal;
93  }
94 
96  {
97  DiagnosticNodelet::onInit();
98  pnh_->param("gauss_param_set", gauss_param_set_, false);
99  pnh_->param("search_radius", search_radius_, 0.03);
100  pnh_->param("use_polynomial_fit", use_polynomial_fit_, false);
101  pnh_->param("polynomial_order", polynomial_order_, 2);
102  pnh_->param("calc_normal", calc_normal_, true);
103  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
104  dynamic_reconfigure::Server<Config>::CallbackType f =
105  boost::bind(&MovingLeastSquareSmoothing::configCallback, this, _1, _2);
106  srv_->setCallback(f);
107  pub_ =advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
109  }
110 }
111 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MovingLeastSquareSmoothing, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
virtual void configCallback(Config &config, uint32_t level)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void smooth(const sensor_msgs::PointCloud2ConstPtr &input)
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47