octree_change_publisher_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Yuto Inagaki and 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 
38 
39 namespace jsk_pcl_ros
40 {
42  {
43  ConnectionBasedNodelet::onInit();
44  counter_ = 0;
45 
46  pnh_->param("resolution", resolution_, 0.02);
47  pnh_->param("noise_filter", noise_filter_, 2);
48 
49  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
50  dynamic_reconfigure::Server<Config>::CallbackType f =
51  boost::bind(&OctreeChangePublisher::config_callback, this, _1, _2);
52  srv_->setCallback(f);
53 
54  octree_ = new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(resolution_);
55 
56  filtered_cloud.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
57 
58  diff_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "octree_change_result", 1);
59 
61  }
62 
64  {
65  sub_ = pnh_->subscribe("input", 1, &OctreeChangePublisher::cloud_cb,this);
66  }
67 
69  {
70  sub_.shutdown();
71  }
72 
73  void OctreeChangePublisher::config_callback(Config &config, uint32_t level)
74  {
75  boost::mutex::scoped_lock lock(mtx_);
76  if(resolution_ != config.resolution){
77  resolution_ = config.resolution;
78  octree_ = new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(resolution_);
79  counter_ = 0;
80  }
81 
82  noise_filter_ = config.noise_filter;
83  }
84 
85  void OctreeChangePublisher::cloud_cb(const sensor_msgs::PointCloud2 &pc)
86  {
87  if(pc.fields.size() <= 0){
88  return;
89  }
90 
91  boost::mutex::scoped_lock lock(mtx_);
92  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
93  std::vector<int> indices;
94  pcl::fromROSMsg(pc, *cloud);
95  octree_->setInputCloud (cloud);
96  octree_->addPointsFromInputCloud ();
97 
98  if (counter_ != 0){
99  boost::shared_ptr<std::vector<int> > newPointIdxVector (new std::vector<int>);
100 
101  octree_->getPointIndicesFromNewVoxels (*newPointIdxVector, noise_filter_);
102 
103  filtered_cloud.reset (new pcl::PointCloud<pcl::PointXYZRGB>);
104  filtered_cloud->points.reserve(newPointIdxVector->size());
105 
106  for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); it++)
107  filtered_cloud->points.push_back(cloud->points[*it]);
108 
109  sensor_msgs::PointCloud2 octree_change_pointcloud2;
110  pcl::toROSMsg(*filtered_cloud, octree_change_pointcloud2);
111  octree_change_pointcloud2.header = pc.header;
112  octree_change_pointcloud2.is_dense = false;
113  diff_pub_.publish(octree_change_pointcloud2);
114  }
115 
116  octree_->switchBuffers ();
117  counter_++;
118  }
119 }
120 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr filtered_cloud
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
pcl::octree::OctreePointCloudChangeDetector< pcl::PointXYZRGB > * octree_
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void cloud_cb(const sensor_msgs::PointCloud2 &pc)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::OctreeChangePublisher, nodelet::Nodelet)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
Realtime change detection of pointcloud using octree. See paper below:
cloud
virtual void config_callback(Config &config, uint32_t level)


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