
Private Types | |
| typedef pcl::PointCloud < pcl::PointXYZ >  | PointCloud | 
Private Member Functions | |
| void | connectCb () | 
| template<typename T > | |
| void | convert (const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg) | 
| void | depthCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) | 
| virtual void | onInit () | 
Private Attributes | |
| boost::mutex | connect_mutex_ | 
| boost::shared_ptr < image_transport::ImageTransport >  | it_ | 
| image_geometry::PinholeCameraModel | model_ | 
| ros::Publisher | pub_point_cloud_ | 
| int | queue_size_ | 
| image_transport::CameraSubscriber | sub_depth_ | 
Definition at line 15 of file point_cloud_xyz.cpp.
typedef pcl::PointCloud<pcl::PointXYZ> depth_image_proc::PointCloudXyzNodelet::PointCloud [private] | 
        
Definition at line 24 of file point_cloud_xyz.cpp.
| void depth_image_proc::PointCloudXyzNodelet::connectCb | ( | ) |  [private] | 
        
Definition at line 58 of file point_cloud_xyz.cpp.
| void depth_image_proc::PointCloudXyzNodelet::convert | ( | const sensor_msgs::ImageConstPtr & | depth_msg, | 
| PointCloud::Ptr & | cloud_msg | ||
| ) |  [private] | 
        
Definition at line 103 of file point_cloud_xyz.cpp.
| void depth_image_proc::PointCloudXyzNodelet::depthCb | ( | const sensor_msgs::ImageConstPtr & | depth_msg, | 
| const sensor_msgs::CameraInfoConstPtr & | info_msg | ||
| ) |  [private] | 
        
Definition at line 72 of file point_cloud_xyz.cpp.
| void depth_image_proc::PointCloudXyzNodelet::onInit | ( | ) |  [private, virtual] | 
        
Implements nodelet::Nodelet.
Definition at line 41 of file point_cloud_xyz.cpp.
boost::mutex depth_image_proc::PointCloudXyzNodelet::connect_mutex_ [private] | 
        
Definition at line 23 of file point_cloud_xyz.cpp.
boost::shared_ptr<image_transport::ImageTransport> depth_image_proc::PointCloudXyzNodelet::it_ [private] | 
        
Definition at line 18 of file point_cloud_xyz.cpp.
Definition at line 27 of file point_cloud_xyz.cpp.
Definition at line 25 of file point_cloud_xyz.cpp.
int depth_image_proc::PointCloudXyzNodelet::queue_size_ [private] | 
        
Definition at line 20 of file point_cloud_xyz.cpp.
Definition at line 19 of file point_cloud_xyz.cpp.