$search

PointCloudColorizer Class Reference

List of all members.

Public Member Functions

void cloud_cb (const sensor_msgs::PointCloud2ConstPtr &pc)
void cloud_cb (const sensor_msgs::PointCloud2ConstPtr &pc)
float getRGB (float r, float g, float b)
float getRGB (float r, float g, float b)
void image_cb (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
void image_cb (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
void move_head (std::string frame_id, double x, double y, double z)
 PointCloudColorizer (ros::NodeHandle &n)
 PointCloudColorizer (ros::NodeHandle &n)
void process (cv::Mat image)
void process (pcl::PointCloud< pcl::PointXYZ > &cloud_in, cv::Mat image)
void spin ()
 ~PointCloudColorizer ()

Private Attributes

sensor_msgs::CvBridge bridge_
image_geometry::PinholeCameraModel cam_model_
pcl::PointCloud< pcl::PointXYZ > cloud_in_
pcl::PointCloud< pcl::PointXYZ > cloud_in_tranformed_
boost::mutex cloud_lock_
std::vector< pcl::PointCloud
< pcl::PointXYZ > > 
cloud_queue_
bool cloud_received_
std::string cloud_rgb_topic_
ros::Subscriber cloud_sub_
boost::shared_ptr
< pcl::PointCloud
< pcl::PointXYZRGB > > 
cloud_xyzrgb_
cv::Mat image_
bool image_received_
image_transport::CameraSubscriber image_sub_
std::string input_cloud_topic_
std::string input_image_topic_
image_transport::ImageTransport it_
bool monochrome_
bool move_head_
double move_offset_x_
double move_offset_y_max_
double move_offset_y_min_
double move_offset_z_max_
double move_offset_z_min_
ros::NodeHandle nh_
sensor_msgs::PointCloud2::Ptr output_cloud_ptr_
PointHeadClientpoint_head_client_
ros::Publisher pub_output_
std::map< int, std::pair< int,
int32_t > > 
rgb_average_
cv::Mat ros_image_
bool save_image_
boost::thread spin_thread_
ros::Time stamp_
double step_y_
double step_z_
tf::TransformListener tf_listener_

Detailed Description

Definition at line 21 of file pointcloud_colorizer.cpp.


Constructor & Destructor Documentation

PointCloudColorizer::PointCloudColorizer ( ros::NodeHandle n  )  [inline]

Definition at line 44 of file pointcloud_colorizer.cpp.

PointCloudColorizer::PointCloudColorizer ( ros::NodeHandle n  )  [inline]

Definition at line 64 of file pointcloud_colorizer_with_head_movement.cpp.

PointCloudColorizer::~PointCloudColorizer (  )  [inline]

Definition at line 101 of file pointcloud_colorizer_with_head_movement.cpp.


Member Function Documentation

void PointCloudColorizer::cloud_cb ( const sensor_msgs::PointCloud2ConstPtr pc  )  [inline]

Definition at line 106 of file pointcloud_colorizer_with_head_movement.cpp.

void PointCloudColorizer::cloud_cb ( const sensor_msgs::PointCloud2ConstPtr pc  )  [inline]

Definition at line 60 of file pointcloud_colorizer.cpp.

float PointCloudColorizer::getRGB ( float  r,
float  g,
float  b 
) [inline]

Definition at line 139 of file pointcloud_colorizer_with_head_movement.cpp.

float PointCloudColorizer::getRGB ( float  r,
float  g,
float  b 
) [inline]

Definition at line 71 of file pointcloud_colorizer.cpp.

void PointCloudColorizer::image_cb ( const sensor_msgs::ImageConstPtr image_msg,
const sensor_msgs::CameraInfoConstPtr info_msg 
) [inline]

Definition at line 146 of file pointcloud_colorizer_with_head_movement.cpp.

void PointCloudColorizer::image_cb ( const sensor_msgs::ImageConstPtr image_msg,
const sensor_msgs::CameraInfoConstPtr info_msg 
) [inline]

Definition at line 78 of file pointcloud_colorizer.cpp.

void PointCloudColorizer::move_head ( std::string  frame_id,
double  x,
double  y,
double  z 
) [inline]

Definition at line 178 of file pointcloud_colorizer_with_head_movement.cpp.

void PointCloudColorizer::process ( cv::Mat  image  )  [inline]

Definition at line 219 of file pointcloud_colorizer_with_head_movement.cpp.

void PointCloudColorizer::process ( pcl::PointCloud< pcl::PointXYZ > &  cloud_in,
cv::Mat  image 
) [inline]

Definition at line 101 of file pointcloud_colorizer.cpp.

void PointCloudColorizer::spin (  )  [inline]

Definition at line 329 of file pointcloud_colorizer_with_head_movement.cpp.


Member Data Documentation

Definition at line 31 of file pointcloud_colorizer.cpp.

Definition at line 40 of file pointcloud_colorizer.cpp.

pcl::PointCloud< pcl::PointXYZ > PointCloudColorizer::cloud_in_ [private]

Definition at line 35 of file pointcloud_colorizer.cpp.

pcl::PointCloud< pcl::PointXYZ > PointCloudColorizer::cloud_in_tranformed_ [private]

Definition at line 35 of file pointcloud_colorizer.cpp.

boost::mutex PointCloudColorizer::cloud_lock_ [private]

Definition at line 37 of file pointcloud_colorizer.cpp.

std::vector< pcl::PointCloud< pcl::PointXYZ > > PointCloudColorizer::cloud_queue_ [private]

Definition at line 38 of file pointcloud_colorizer.cpp.

Definition at line 41 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 32 of file pointcloud_colorizer.cpp.

Definition at line 26 of file pointcloud_colorizer.cpp.

boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB> > PointCloudColorizer::cloud_xyzrgb_ [private]

Definition at line 60 of file pointcloud_colorizer_with_head_movement.cpp.

cv::Mat PointCloudColorizer::image_ [private]

Definition at line 36 of file pointcloud_colorizer.cpp.

Definition at line 41 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 25 of file pointcloud_colorizer.cpp.

Definition at line 32 of file pointcloud_colorizer.cpp.

Definition at line 32 of file pointcloud_colorizer.cpp.

Definition at line 30 of file pointcloud_colorizer.cpp.

Definition at line 33 of file pointcloud_colorizer.cpp.

Definition at line 41 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 58 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 56 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 56 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 57 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 57 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 24 of file pointcloud_colorizer.cpp.

Definition at line 41 of file pointcloud_colorizer.cpp.

Definition at line 54 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 42 of file pointcloud_colorizer.cpp.

std::map<int, std::pair<int, int32_t> > PointCloudColorizer::rgb_average_ [private]

Definition at line 62 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 44 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 33 of file pointcloud_colorizer.cpp.

boost::thread PointCloudColorizer::spin_thread_ [private]

Definition at line 61 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 59 of file pointcloud_colorizer_with_head_movement.cpp.

double PointCloudColorizer::step_y_ [private]

Definition at line 56 of file pointcloud_colorizer_with_head_movement.cpp.

double PointCloudColorizer::step_z_ [private]

Definition at line 57 of file pointcloud_colorizer_with_head_movement.cpp.

Definition at line 28 of file pointcloud_colorizer.cpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


image_algos
Author(s): Dejan Pangercic
autogenerated on Tue Dec 4 10:08:31 2012