uniform_sampling_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
39 #include <pcl/keypoints/uniform_sampling.h>
40 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
41 #include <pcl/filters/uniform_sampling.h>
42 #endif
43 
44 
45 namespace jsk_pcl_ros
46 {
48  {
49  DiagnosticNodelet::onInit();
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  typename dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind (&UniformSampling::configCallback, this, _1, _2);
53  srv_->setCallback (f);
54 
55  pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
56 
58  }
59 
61  {
62  sub_ = pnh_->subscribe("input", 1, &UniformSampling::sampling, this);
63  }
64 
66  {
67  sub_.shutdown();
68  }
69 
70  void UniformSampling::configCallback(Config& config, uint32_t level)
71  {
72  boost::mutex::scoped_lock lock(mutex_);
73  search_radius_ = config.search_radius;
74  }
75 
77  const sensor_msgs::PointCloud2::ConstPtr& msg)
78  {
79  boost::mutex::scoped_lock lock(mutex_);
80  pcl::PointCloud<pcl::PointXYZ>::Ptr
81  cloud (new pcl::PointCloud<pcl::PointXYZ>);
82  pcl::fromROSMsg(*msg, *cloud);
83  pcl::UniformSampling<pcl::PointXYZ> uniform_sampling;
84  uniform_sampling.setInputCloud(cloud);
85  uniform_sampling.setRadiusSearch(search_radius_);
86 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
87  pcl::PointCloud<int> indices;
88  uniform_sampling.compute(indices);
89 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
90  pcl::PointCloud<pcl::PointXYZ> output;
91  uniform_sampling.filter(output);
92  pcl::PointIndicesPtr indices_ptr;
93  std::vector<int> &indices = *uniform_sampling.getIndices();
94 #endif
95  PCLIndicesMsg ros_indices;
96 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
97  for (size_t i = 0; i < indices.points.size(); i++) {
98  ros_indices.indices.push_back(indices.points[i]);
99  }
100 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
101  for (size_t i = 0; i < indices.size(); i++) {
102  ros_indices.indices.push_back(indices[i]);
103  }
104 #endif
105  ros_indices.header = msg->header;
106  pub_.publish(ros_indices);
107  }
108 }
109 
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< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::UniformSampling, nodelet::Nodelet)
UniformSamplingConfig Config
void output(int index, double value)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void sampling(const sensor_msgs::PointCloud2::ConstPtr &msg)
pcl::PointIndices PCLIndicesMsg
cloud


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