#include <octree_change_publisher.h>

Protected Member Functions | |
| virtual void | cloud_cb (const sensor_msgs::PointCloud2 &pc) |
| virtual void | subscribe () |
| virtual void | unsubscribe () |
Protected Attributes | |
| int | counter_ |
| ros::Publisher | diff_pub_ |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | filtered_cloud |
| int | noise_filter_ |
| pcl::octree::OctreePointCloudChangeDetector < pcl::PointXYZRGB > * | octree_ |
| double | resolution_ |
| ros::Subscriber | sub_ |
Private Member Functions | |
| virtual void | onInit () |
Definition at line 53 of file octree_change_publisher.h.
| void jsk_pcl_ros::OctreeChangePublisher::cloud_cb | ( | const sensor_msgs::PointCloud2 & | pc | ) | [protected, virtual] |
Definition at line 66 of file octree_change_publisher_nodelet.cpp.
| void jsk_pcl_ros::OctreeChangePublisher::onInit | ( | void | ) | [private, virtual] |
Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 41 of file octree_change_publisher_nodelet.cpp.
| void jsk_pcl_ros::OctreeChangePublisher::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 56 of file octree_change_publisher_nodelet.cpp.
| void jsk_pcl_ros::OctreeChangePublisher::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 61 of file octree_change_publisher_nodelet.cpp.
int jsk_pcl_ros::OctreeChangePublisher::counter_ [protected] |
Definition at line 56 of file octree_change_publisher.h.
Definition at line 61 of file octree_change_publisher.h.
pcl::PointCloud<pcl::PointXYZRGB>::Ptr jsk_pcl_ros::OctreeChangePublisher::filtered_cloud [protected] |
Definition at line 63 of file octree_change_publisher.h.
int jsk_pcl_ros::OctreeChangePublisher::noise_filter_ [protected] |
Definition at line 57 of file octree_change_publisher.h.
pcl::octree::OctreePointCloudChangeDetector<pcl::PointXYZRGB>* jsk_pcl_ros::OctreeChangePublisher::octree_ [protected] |
Definition at line 62 of file octree_change_publisher.h.
double jsk_pcl_ros::OctreeChangePublisher::resolution_ [protected] |
Definition at line 58 of file octree_change_publisher.h.
Definition at line 60 of file octree_change_publisher.h.