36 #ifndef __JSK_PCL_ROS_OCTREE_CHANGE_PUBLISHER_H__ 37 #define __JSK_PCL_ROS_OCTREE_CHANGE_PUBLISHER_H__ 41 #include <sensor_msgs/PointCloud2.h> 42 #include <dynamic_reconfigure/server.h> 43 #include <jsk_pcl_ros/OctreeChangePublisherConfig.h> 48 #include <pcl/point_types.h> 49 #include <pcl/point_cloud.h> 50 #include <pcl/octree/octree.h> 73 typedef OctreeChangePublisherConfig
Config;
82 pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB> *
octree_;
87 cloud_cb (
const sensor_msgs::PointCloud2 &pc);
pcl::PointCloud< pcl::PointXYZRGB >::Ptr filtered_cloud
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void unsubscribe()
OctreeChangePublisherConfig Config
pcl::octree::OctreePointCloudChangeDetector< pcl::PointXYZRGB > * octree_
virtual void cloud_cb(const sensor_msgs::PointCloud2 &pc)
Realtime change detection of pointcloud using octree. See paper below:
boost::mutex mutex
global mutex.
virtual void config_callback(Config &config, uint32_t level)