|
void | connectCb () |
|
template<typename T , typename T2 > |
void | convert (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg, const PointCloud::Ptr &cloud_msg) |
|
void | imageCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
|
virtual void | onInit () |
|
Definition at line 91 of file point_cloud_xyzi.cpp.
◆ PointCloud
◆ Synchronizer
◆ SyncPolicy
◆ connectCb()
void depth_image_proc::PointCloudXyziNodelet::connectCb |
( |
| ) |
|
|
private |
◆ convert()
template<typename T , typename T2 >
void depth_image_proc::PointCloudXyziNodelet::convert |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
const sensor_msgs::ImageConstPtr & |
intensity_msg, |
|
|
const PointCloud::Ptr & |
cloud_msg |
|
) |
| |
|
private |
◆ imageCb()
void depth_image_proc::PointCloudXyziNodelet::imageCb |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
const sensor_msgs::ImageConstPtr & |
intensity_msg, |
|
|
const sensor_msgs::CameraInfoConstPtr & |
info_msg |
|
) |
| |
|
private |
◆ onInit()
void depth_image_proc::PointCloudXyziNodelet::onInit |
( |
| ) |
|
|
privatevirtual |
◆ connect_mutex_
boost::mutex depth_image_proc::PointCloudXyziNodelet::connect_mutex_ |
|
private |
◆ depth_it_
◆ intensity_it_
◆ intensity_nh_
◆ model_
◆ pub_point_cloud_
ros::Publisher depth_image_proc::PointCloudXyziNodelet::pub_point_cloud_ |
|
private |
◆ sub_depth_
◆ sub_info_
◆ sub_intensity_
◆ sync_
The documentation for this class was generated from the following file: