Private Types | |
typedef sensor_msgs::PointCloud2 | 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 | |
cv::Mat | binned |
boost::mutex | connect_mutex_ |
std::vector< double > | D_ |
int | height_ |
boost::shared_ptr < image_transport::ImageTransport > | it_ |
boost::array< double, 9 > | K_ |
ros::Publisher | pub_point_cloud_ |
int | queue_size_ |
image_transport::CameraSubscriber | sub_depth_ |
int | width_ |
Definition at line 48 of file point_cloud_xyz_radial.cpp.
typedef sensor_msgs::PointCloud2 depth_image_proc::PointCloudXyzRadialNodelet::PointCloud [private] |
Definition at line 57 of file point_cloud_xyz_radial.cpp.
void depth_image_proc::PointCloudXyzRadialNodelet::connectCb | ( | ) | [private] |
Definition at line 141 of file point_cloud_xyz_radial.cpp.
void depth_image_proc::PointCloudXyzRadialNodelet::convert | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
PointCloud::Ptr & | cloud_msg | ||
) | [private] |
Definition at line 199 of file point_cloud_xyz_radial.cpp.
void depth_image_proc::PointCloudXyzRadialNodelet::depthCb | ( | const sensor_msgs::ImageConstPtr & | depth_msg, |
const sensor_msgs::CameraInfoConstPtr & | info_msg | ||
) | [private] |
Definition at line 158 of file point_cloud_xyz_radial.cpp.
void depth_image_proc::PointCloudXyzRadialNodelet::onInit | ( | ) | [private, virtual] |
Implements nodelet::Nodelet.
Definition at line 123 of file point_cloud_xyz_radial.cpp.
cv::Mat depth_image_proc::PointCloudXyzRadialNodelet::binned [private] |
Definition at line 67 of file point_cloud_xyz_radial.cpp.
boost::mutex depth_image_proc::PointCloudXyzRadialNodelet::connect_mutex_ [private] |
Definition at line 56 of file point_cloud_xyz_radial.cpp.
std::vector<double> depth_image_proc::PointCloudXyzRadialNodelet::D_ [private] |
Definition at line 61 of file point_cloud_xyz_radial.cpp.
int depth_image_proc::PointCloudXyzRadialNodelet::height_ [private] |
Definition at line 65 of file point_cloud_xyz_radial.cpp.
boost::shared_ptr<image_transport::ImageTransport> depth_image_proc::PointCloudXyzRadialNodelet::it_ [private] |
Definition at line 51 of file point_cloud_xyz_radial.cpp.
boost::array<double, 9> depth_image_proc::PointCloudXyzRadialNodelet::K_ [private] |
Definition at line 62 of file point_cloud_xyz_radial.cpp.
Definition at line 58 of file point_cloud_xyz_radial.cpp.
Definition at line 53 of file point_cloud_xyz_radial.cpp.
image_transport::CameraSubscriber depth_image_proc::PointCloudXyzRadialNodelet::sub_depth_ [private] |
Definition at line 52 of file point_cloud_xyz_radial.cpp.
int depth_image_proc::PointCloudXyzRadialNodelet::width_ [private] |
Definition at line 64 of file point_cloud_xyz_radial.cpp.