Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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 octree_ = new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(resolution_);
00050
00051 filtered_cloud.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
00052
00053 diff_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "octree_change_result", 1);
00054 }
00055
00056 void OctreeChangePublisher::subscribe()
00057 {
00058 sub_ = pnh_->subscribe("input", 1, &OctreeChangePublisher::cloud_cb,this);
00059 }
00060
00061 void OctreeChangePublisher::unsubscribe()
00062 {
00063 sub_.shutdown();
00064 }
00065
00066 void OctreeChangePublisher::cloud_cb(const sensor_msgs::PointCloud2 &pc)
00067 {
00068 if(pc.fields.size() <= 0){
00069 return;
00070 }
00071
00072 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00073 std::vector<int> indices;
00074 pcl::fromROSMsg(pc, *cloud);
00075 octree_->setInputCloud (cloud);
00076 octree_->addPointsFromInputCloud ();
00077
00078 if (counter_ != 0){
00079 boost::shared_ptr<std::vector<int> > newPointIdxVector (new std::vector<int>);
00080
00081 octree_->getPointIndicesFromNewVoxels (*newPointIdxVector, noise_filter_);
00082
00083 filtered_cloud.reset (new pcl::PointCloud<pcl::PointXYZRGB>);
00084 filtered_cloud->points.reserve(newPointIdxVector->size());
00085
00086 for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); it++)
00087 filtered_cloud->points.push_back(cloud->points[*it]);
00088
00089 sensor_msgs::PointCloud2 octree_change_pointcloud2;
00090 pcl::toROSMsg(*filtered_cloud, octree_change_pointcloud2);
00091 octree_change_pointcloud2.header = pc.header;
00092 octree_change_pointcloud2.is_dense = false;
00093 diff_pub_.publish(octree_change_pointcloud2);
00094 }
00095
00096 octree_->switchBuffers ();
00097 counter_++;
00098 }
00099 }
00100
00101 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OctreeChangePublisher, nodelet::Nodelet);