43 ConnectionBasedNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
54 octree_ =
new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(
resolution_);
58 diff_pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"octree_change_result", 1);
75 boost::mutex::scoped_lock
lock(
mtx_);
78 octree_ =
new pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>(
resolution_);
87 if(pc.fields.size() <= 0){
91 boost::mutex::scoped_lock
lock(
mtx_);
92 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZRGB>());
93 std::vector<int> indices;
96 octree_->addPointsFromInputCloud ();
106 for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); it++)
109 sensor_msgs::PointCloud2 octree_change_pointcloud2;
111 octree_change_pointcloud2.header = pc.header;
112 octree_change_pointcloud2.is_dense =
false;
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)
virtual void unsubscribe()
OctreeChangePublisherConfig Config
pcl::octree::OctreePointCloudChangeDetector< pcl::PointXYZRGB > * octree_
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:
virtual void config_callback(Config &config, uint32_t level)