octree_change_publisher_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Yuto Inagaki and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 
00036 #include "jsk_pcl_ros/octree_change_publisher.h"
00037 #include <pluginlib/class_list_macros.h>
00038 
00039 namespace jsk_pcl_ros
00040 {
00041   void OctreeChangePublisher::onInit(void)
00042   {
00043     ConnectionBasedNodelet::onInit();
00044     counter_ = 0;
00045 
00046     pnh_->param("resolution", resolution_, 0.02);
00047     pnh_->param("noise_filter", noise_filter_, 2);
00048 
00049     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
00050     dynamic_reconfigure::Server<Config>::CallbackType f =
00051       boost::bind(&OctreeChangePublisher::config_callback, this, _1, _2);
00052     srv_->setCallback(f);
00053 
00054     octree_ = new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(resolution_);
00055 
00056     filtered_cloud.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
00057 
00058     diff_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "octree_change_result", 1);
00059 
00060     onInitPostProcess();
00061   }
00062 
00063   void OctreeChangePublisher::subscribe()
00064   {
00065     sub_ = pnh_->subscribe("input", 1, &OctreeChangePublisher::cloud_cb,this);
00066   }
00067 
00068   void OctreeChangePublisher::unsubscribe()
00069   {
00070     sub_.shutdown();
00071   }
00072 
00073   void OctreeChangePublisher::config_callback(Config &config, uint32_t level)
00074   {
00075     boost::mutex::scoped_lock lock(mtx_);
00076     if(resolution_ != config.resolution){
00077       resolution_ = config.resolution;
00078       octree_ = new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(resolution_);
00079       counter_ = 0;
00080     }
00081 
00082     noise_filter_ = config.noise_filter;
00083   }
00084 
00085   void OctreeChangePublisher::cloud_cb(const sensor_msgs::PointCloud2 &pc)
00086   {
00087     if(pc.fields.size() <= 0){
00088       return;
00089     }
00090 
00091     boost::mutex::scoped_lock lock(mtx_);
00092     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00093     std::vector<int> indices;
00094     pcl::fromROSMsg(pc, *cloud);
00095     octree_->setInputCloud (cloud);
00096     octree_->addPointsFromInputCloud ();
00097 
00098     if (counter_ != 0){
00099       boost::shared_ptr<std::vector<int> > newPointIdxVector (new std::vector<int>);
00100 
00101       octree_->getPointIndicesFromNewVoxels (*newPointIdxVector, noise_filter_);
00102 
00103       filtered_cloud.reset (new pcl::PointCloud<pcl::PointXYZRGB>);
00104       filtered_cloud->points.reserve(newPointIdxVector->size());
00105 
00106       for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); it++)
00107         filtered_cloud->points.push_back(cloud->points[*it]);
00108 
00109       sensor_msgs::PointCloud2 octree_change_pointcloud2;
00110       pcl::toROSMsg(*filtered_cloud, octree_change_pointcloud2);
00111       octree_change_pointcloud2.header = pc.header;
00112       octree_change_pointcloud2.is_dense = false;
00113       diff_pub_.publish(octree_change_pointcloud2);
00114     }
00115 
00116     octree_->switchBuffers ();
00117     counter_++;
00118   }
00119 }
00120 
00121 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OctreeChangePublisher, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50