bilateral_filter_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <pcl_ros/publisher.h>
38 // on hydro, we cannot include this header because of bug of pcl
39 //#include <pcl/point_types_conversion.h>
40 #include <pcl/filters/bilateral.h>
41 #include <pcl/filters/fast_bilateral.h>
42 #include <pcl/filters/fast_bilateral_omp.h>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  ConnectionBasedNodelet::onInit();
49  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50  typename dynamic_reconfigure::Server<Config>::CallbackType f =
51  boost::bind (&BilateralFilter::configCallback, this, _1, _2);
52  srv_->setCallback (f);
53 
54  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
55 
57  }
58 
60  {
61  sub_ = pnh_->subscribe("input", 1, &BilateralFilter::filter, this);
62  }
63 
65  {
66  sub_.shutdown();
67  }
68 
69  void BilateralFilter::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
70  {
71  boost::mutex::scoped_lock lock(mutex_);
72  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
73  pcl::PointCloud<PointT>::Ptr
74  output (new pcl::PointCloud<PointT>);
75  pcl::fromROSMsg(*msg, *cloud);
76  pcl::FastBilateralFilter<PointT> bilateral;
77 
78  bilateral.setInputCloud(cloud);
79  bilateral.setSigmaS(sigma_s_);
80  bilateral.setSigmaR(sigma_r_);
81  bilateral.filter(*output);
82  sensor_msgs::PointCloud2 ros_output;
83  pcl::toROSMsg(*output, ros_output);
84  ros_output.header = msg->header;
85  // hmm,,, is it keep organized??
86  pub_.publish(ros_output);
87  }
88 
89  void BilateralFilter::configCallback(Config &config, uint32_t level)
90  {
91  boost::mutex::scoped_lock lock(mutex_);
92  sigma_s_ = config.sigma_s;
93  sigma_r_ = config.sigma_r;
94  }
95 
96 }
97 
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BilateralFilter, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
BilateralFilterConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void output(int index, double value)
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
cloud


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