Public Types | Protected Member Functions | Protected Attributes | Private Member Functions
jsk_pcl_ros::OctreeChangePublisher Class Reference

Realtime change detection of pointcloud using octree. See paper below: More...

#include <octree_change_publisher.h>

Inheritance diagram for jsk_pcl_ros::OctreeChangePublisher:
Inheritance graph
[legend]

List of all members.

Public Types

typedef OctreeChangePublisherConfig Config

Protected Member Functions

virtual void cloud_cb (const sensor_msgs::PointCloud2 &pc)
virtual void config_callback (Config &config, uint32_t level)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

int counter_
ros::Publisher diff_pub_
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
filtered_cloud
boost::mutex mtx_
int noise_filter_
pcl::octree::OctreePointCloudChangeDetector
< pcl::PointXYZRGB > * 
octree_
double resolution_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_

Private Member Functions

virtual void onInit ()

Detailed Description

Realtime change detection of pointcloud using octree. See paper below:

{6224647, author={Kammerl, J. and Blodow, N. and Rusu, R.B. and Gedikli, S. and Beetz, M. and Steinbach, E.}, booktitle={Robotics and Automation (ICRA), 2012 IEEE International Conference on}, title={Real-time compression of point cloud streams}, year={2012}, pages={778-785}, keywords={cloud computing;data compression;tree data structures;coding complexity;coding precision;novel lossy compression approach;octree data structures;point cloud streams;real-time compression;spatial decomposition;temporal redundancy;Decoding;Encoding;Entropy;Octrees;Real time systems;Sensors}, doi={10.1109/ICRA.2012.6224647}, ISSN={1050-4729}, month={May},}

Definition at line 70 of file octree_change_publisher.h.


Member Typedef Documentation

typedef OctreeChangePublisherConfig jsk_pcl_ros::OctreeChangePublisher::Config

Definition at line 73 of file octree_change_publisher.h.


Member Function Documentation

void jsk_pcl_ros::OctreeChangePublisher::cloud_cb ( const sensor_msgs::PointCloud2 &  pc) [protected, virtual]

Definition at line 85 of file octree_change_publisher_nodelet.cpp.

void jsk_pcl_ros::OctreeChangePublisher::config_callback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 73 of file octree_change_publisher_nodelet.cpp.

void jsk_pcl_ros::OctreeChangePublisher::onInit ( void  ) [private, virtual]

Definition at line 41 of file octree_change_publisher_nodelet.cpp.

void jsk_pcl_ros::OctreeChangePublisher::subscribe ( ) [protected, virtual]

Definition at line 63 of file octree_change_publisher_nodelet.cpp.

void jsk_pcl_ros::OctreeChangePublisher::unsubscribe ( ) [protected, virtual]

Definition at line 68 of file octree_change_publisher_nodelet.cpp.


Member Data Documentation

Definition at line 75 of file octree_change_publisher.h.

Definition at line 81 of file octree_change_publisher.h.

Definition at line 83 of file octree_change_publisher.h.

Definition at line 78 of file octree_change_publisher.h.

Definition at line 76 of file octree_change_publisher.h.

pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>* jsk_pcl_ros::OctreeChangePublisher::octree_ [protected]

Definition at line 82 of file octree_change_publisher.h.

Definition at line 77 of file octree_change_publisher.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::OctreeChangePublisher::srv_ [protected]

Definition at line 84 of file octree_change_publisher.h.

Definition at line 80 of file octree_change_publisher.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:47