Public Member Functions | Private Member Functions | Private Attributes
PCLtoImage Class Reference

#include <pcl_to_image.h>

List of all members.

Public Member Functions

 PCLtoImage ()

Private Member Functions

void image_from_sparse_pcl2 (pcl::PointCloud< pcl::PointXYZRGB > cloud, cv::Mat &rgb_image)
void pcl2_sub_callback (const sensor_msgs::PointCloud2::ConstPtr &msg)

Private Attributes

double cloud_remaining_proportion_threshold_
cv_bridge::CvImage cv_image
double distance_threshold_
sensor_msgs::Image image_msg_
image_transport::Publisher image_pub_
image_transport::ImageTransport it_
CMutex mutex
ros::NodeHandle nh_
ros::Subscriber pcl2_sub_
pcl::PointCloud< pcl::PointXYZ > pcl_xyzrgb2_
pcl::PointCloud< pcl::PointXYZRGB > pcl_xyzrgb_

Detailed Description

Definition at line 52 of file pcl_to_image.h.


Constructor & Destructor Documentation

Definition at line 6 of file pcl_to_image.cpp.


Member Function Documentation

void PCLtoImage::image_from_sparse_pcl2 ( pcl::PointCloud< pcl::PointXYZRGB >  cloud,
cv::Mat &  rgb_image 
) [private]

retrieves the rgb component of the pointcloud and sets it to an opencv2 image

Definition at line 53 of file pcl_to_image.cpp.

void PCLtoImage::pcl2_sub_callback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [private]

Definition at line 24 of file pcl_to_image.cpp.


Member Data Documentation

Definition at line 59 of file pcl_to_image.h.

Definition at line 63 of file pcl_to_image.h.

Definition at line 58 of file pcl_to_image.h.

sensor_msgs::Image PCLtoImage::image_msg_ [private]

Definition at line 65 of file pcl_to_image.h.

Definition at line 82 of file pcl_to_image.h.

Definition at line 81 of file pcl_to_image.h.

CMutex PCLtoImage::mutex [private]

Definition at line 61 of file pcl_to_image.h.

Definition at line 67 of file pcl_to_image.h.

Definition at line 78 of file pcl_to_image.h.

pcl::PointCloud<pcl::PointXYZ> PCLtoImage::pcl_xyzrgb2_ [private]

Definition at line 70 of file pcl_to_image.h.

pcl::PointCloud<pcl::PointXYZRGB> PCLtoImage::pcl_xyzrgb_ [private]

Definition at line 69 of file pcl_to_image.h.


The documentation for this class was generated from the following files:


iri_pcl_filters
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 20:44:42