|
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 () |
|
Definition at line 81 of file point_cloud_xyz_radial.cpp.
◆ PointCloud
◆ connectCb()
void depth_image_proc::PointCloudXyzRadialNodelet::connectCb |
( |
| ) |
|
|
private |
◆ convert()
template<typename T >
void depth_image_proc::PointCloudXyzRadialNodelet::convert |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
PointCloud::Ptr & |
cloud_msg |
|
) |
| |
|
private |
◆ depthCb()
void depth_image_proc::PointCloudXyzRadialNodelet::depthCb |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
const sensor_msgs::CameraInfoConstPtr & |
info_msg |
|
) |
| |
|
private |
◆ onInit()
void depth_image_proc::PointCloudXyzRadialNodelet::onInit |
( |
| ) |
|
|
privatevirtual |
◆ binned
cv::Mat depth_image_proc::PointCloudXyzRadialNodelet::binned |
|
private |
◆ connect_mutex_
boost::mutex depth_image_proc::PointCloudXyzRadialNodelet::connect_mutex_ |
|
private |
◆ D_
std::vector<double> depth_image_proc::PointCloudXyzRadialNodelet::D_ |
|
private |
◆ height_
int depth_image_proc::PointCloudXyzRadialNodelet::height_ |
|
private |
◆ it_
◆ K_
boost::array<double, 9> depth_image_proc::PointCloudXyzRadialNodelet::K_ |
|
private |
◆ pub_point_cloud_
ros::Publisher depth_image_proc::PointCloudXyzRadialNodelet::pub_point_cloud_ |
|
private |
◆ queue_size_
int depth_image_proc::PointCloudXyzRadialNodelet::queue_size_ |
|
private |
◆ sub_depth_
◆ width_
int depth_image_proc::PointCloudXyzRadialNodelet::width_ |
|
private |
The documentation for this class was generated from the following file: