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/or 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 #include <pcl/search/kdtree.h> // for KdTree
43 
44 namespace jsk_pcl_ros
45 {
46  void MovingLeastSquareSmoothing::smooth(const sensor_msgs::PointCloud2ConstPtr& input)
47  {
48  boost::mutex::scoped_lock lock(mutex_);
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>);
52 
53  std::vector<int> indices;
54  cloud->is_dense = false;
55  pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
56 
57  pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGB> smoother;
58  smoother.setSearchRadius (search_radius_);
59  if (gauss_param_set_) smoother.setSqrGaussParam (gauss_param_set_);
60 #if PCL_VERSION_COMPARE (<, 1, 9, 0) // https://github.com/PointCloudLibrary/pcl/blob/cc08f815a9a5f2a1d3f897fb2bc9d541635792c9/CHANGES.md?plain=1#L1633
61  smoother.setPolynomialFit (use_polynomial_fit_);
62 #endif
63  smoother.setPolynomialOrder (polynomial_order_);
64  smoother.setComputeNormals (calc_normal_);
65 
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);
70 
71  sensor_msgs::PointCloud2 pointcloud2;
72  pcl::toROSMsg(*result_cloud, pointcloud2);
73  pointcloud2.header.frame_id = input->header.frame_id;
74  pointcloud2.header.stamp = input->header.stamp;
75  pub_.publish(pointcloud2);
76  }
77 
79  {
80  sub_input_ = pnh_->subscribe("input", 1, &MovingLeastSquareSmoothing::smooth, this);
81  }
82 
84  {
86  }
87 
88  void MovingLeastSquareSmoothing::configCallback(Config &config, uint32_t level)
89  {
90  boost::mutex::scoped_lock lock(mutex_);
91  search_radius_ = config.search_radius;
92  gauss_param_set_ = config.gauss_param_set;
93  use_polynomial_fit_ = config.use_polynomial_fit;
94  polynomial_order_ = config.polynomial_order;
95  calc_normal_ = config.calc_normal;
96  }
97 
99  {
100  DiagnosticNodelet::onInit();
101  pnh_->param("gauss_param_set", gauss_param_set_, false);
102  pnh_->param("search_radius", search_radius_, 0.03);
103  pnh_->param("use_polynomial_fit", use_polynomial_fit_, false);
104  pnh_->param("polynomial_order", polynomial_order_, 2);
105  pnh_->param("calc_normal", calc_normal_, true);
106  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
107  dynamic_reconfigure::Server<Config>::CallbackType f =
108  boost::bind(&MovingLeastSquareSmoothing::configCallback, this, _1, _2);
109  srv_->setCallback(f);
110  pub_ =advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
111  onInitPostProcess();
112  }
113 }
114 
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
jsk_pcl_ros::MovingLeastSquareSmoothing::sub_input_
ros::Subscriber sub_input_
Definition: moving_least_square_smoothing.h:133
jsk_pcl_ros::MovingLeastSquareSmoothing::mutex_
boost::mutex mutex_
Definition: moving_least_square_smoothing.h:140
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MovingLeastSquareSmoothing, nodelet::Nodelet)
jsk_pcl_ros::MovingLeastSquareSmoothing::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: moving_least_square_smoothing.h:141
jsk_pcl_ros::MovingLeastSquareSmoothing::subscribe
virtual void subscribe()
Definition: moving_least_square_smoothing_nodelet.cpp:78
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros::MovingLeastSquareSmoothing
Definition: moving_least_square_smoothing.h:89
jsk_pcl_ros::MovingLeastSquareSmoothing::polynomial_order_
int polynomial_order_
Definition: moving_least_square_smoothing.h:139
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
cloud
cloud
jsk_pcl_ros::MovingLeastSquareSmoothing::calc_normal_
bool calc_normal_
Definition: moving_least_square_smoothing.h:136
class_list_macros.h
tree
tree
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::MovingLeastSquareSmoothing::onInit
virtual void onInit()
Definition: moving_least_square_smoothing_nodelet.cpp:98
jsk_pcl_ros::MovingLeastSquareSmoothing::gauss_param_set_
bool gauss_param_set_
Definition: moving_least_square_smoothing.h:135
_1
boost::arg< 1 > _1
jsk_pcl_ros::MovingLeastSquareSmoothing::smooth
virtual void smooth(const sensor_msgs::PointCloud2ConstPtr &input)
Definition: moving_least_square_smoothing_nodelet.cpp:46
jsk_pcl_ros::MovingLeastSquareSmoothing::pub_
ros::Publisher pub_
Definition: moving_least_square_smoothing.h:134
pcl_conversion_util.h
nodelet::Nodelet
moving_least_square_smoothing.h
jsk_pcl_ros::MovingLeastSquareSmoothing::use_polynomial_fit_
bool use_polynomial_fit_
Definition: moving_least_square_smoothing.h:138
dump_depth_error.f
f
Definition: dump_depth_error.py:39
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::MovingLeastSquareSmoothing::unsubscribe
virtual void unsubscribe()
Definition: moving_least_square_smoothing_nodelet.cpp:83
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
config
config
jsk_pcl_ros::MovingLeastSquareSmoothing::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: moving_least_square_smoothing_nodelet.cpp:88
jsk_pcl_ros::MovingLeastSquareSmoothing::search_radius_
double search_radius_
Definition: moving_least_square_smoothing.h:137
jsk_pcl_ros::MovingLeastSquareSmoothing::Config
MovingLeastSquareSmoothingConfig Config
Definition: moving_least_square_smoothing.h:124


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45