#include <transform_pointcloud_in_bounding_box.h>

| Public Types | |
| typedef pcl::PointXYZRGB | PointT | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > | SyncPolicy | 
| Protected Member Functions | |
| virtual void | onInit () | 
| virtual void | transform (const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg) | 
| Protected Attributes | |
| ros::Publisher | pub_cloud_ | 
| ros::Publisher | pub_offset_pose_ | 
| message_filters::Subscriber < jsk_recognition_msgs::BoundingBox > | sub_box_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
| tf::TransformListener * | tf_listener_ | 
Definition at line 86 of file transform_pointcloud_in_bounding_box.h.
| typedef pcl::PointXYZRGB jsk_pcl_ros::TransformPointcloudInBoundingBox::PointT | 
Definition at line 89 of file transform_pointcloud_in_bounding_box.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > jsk_pcl_ros::TransformPointcloudInBoundingBox::SyncPolicy | 
Definition at line 92 of file transform_pointcloud_in_bounding_box.h.
| void jsk_pcl_ros::TransformPointcloudInBoundingBox::onInit | ( | void | ) |  [protected, virtual] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 44 of file transform_pointcloud_in_bounding_box_nodelet.cpp.
| void jsk_pcl_ros::TransformPointcloudInBoundingBox::transform | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg, | 
| const jsk_recognition_msgs::BoundingBox::ConstPtr & | box_msg | ||
| ) |  [protected, virtual] | 
Definition at line 67 of file transform_pointcloud_in_bounding_box_nodelet.cpp.
Definition at line 107 of file transform_pointcloud_in_bounding_box.h.
Definition at line 108 of file transform_pointcloud_in_bounding_box.h.
| message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> jsk_pcl_ros::TransformPointcloudInBoundingBox::sub_box_  [protected] | 
Definition at line 105 of file transform_pointcloud_in_bounding_box.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::TransformPointcloudInBoundingBox::sub_input_  [protected] | 
Definition at line 104 of file transform_pointcloud_in_bounding_box.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::TransformPointcloudInBoundingBox::sync_  [protected] | 
Definition at line 106 of file transform_pointcloud_in_bounding_box.h.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 109 of file transform_pointcloud_in_bounding_box.h.