#include <organize_pointcloud.h>

| Protected Member Functions | |
| virtual void | extract (const sensor_msgs::PointCloud2ConstPtr &input) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| double | angle_height | 
| double | angle_width | 
| double | angular_resolution | 
| int | min_points | 
| ros::Publisher | pub_ | 
| ros::Subscriber | sub_ | 
| Private Member Functions | |
| virtual void | onInit () | 
Definition at line 54 of file organize_pointcloud.h.
| void jsk_pcl_ros::OrganizePointCloud::extract | ( | const sensor_msgs::PointCloud2ConstPtr & | input | ) |  [protected, virtual] | 
Definition at line 43 of file organize_pointcloud_nodelet.cpp.
| void jsk_pcl_ros::OrganizePointCloud::onInit | ( | void | ) |  [private, virtual] | 
Definition at line 76 of file organize_pointcloud_nodelet.cpp.
| void jsk_pcl_ros::OrganizePointCloud::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 88 of file organize_pointcloud_nodelet.cpp.
| void jsk_pcl_ros::OrganizePointCloud::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 93 of file organize_pointcloud_nodelet.cpp.
| double jsk_pcl_ros::OrganizePointCloud::angle_height  [protected] | 
Definition at line 57 of file organize_pointcloud.h.
| double jsk_pcl_ros::OrganizePointCloud::angle_width  [protected] | 
Definition at line 57 of file organize_pointcloud.h.
| double jsk_pcl_ros::OrganizePointCloud::angular_resolution  [protected] | 
Definition at line 57 of file organize_pointcloud.h.
| int jsk_pcl_ros::OrganizePointCloud::min_points  [protected] | 
Definition at line 58 of file organize_pointcloud.h.
| ros::Publisher jsk_pcl_ros::OrganizePointCloud::pub_  [protected] | 
Definition at line 60 of file organize_pointcloud.h.
| ros::Subscriber jsk_pcl_ros::OrganizePointCloud::sub_  [protected] | 
Definition at line 59 of file organize_pointcloud.h.