00001 #include <ros/ros.h> 00002 #include <ros/names.h> 00003 00004 #include <sensor_msgs/Image.h> 00005 #include <sensor_msgs/CameraInfo.h> 00006 #include <sensor_msgs/PointCloud.h> 00007 00008 #include <tf/transform_listener.h> 00009 00010 #include <opencv/cv.h> 00011 #include <cv_bridge/cv_bridge.h> 00012 00013 #include "cr_capture/PixelIndices.h" 00014 00015 class CRLib { 00016 private: 00017 sensor_msgs::CameraInfo info_left_, info_right_; 00018 IplImage *ipl_left_, *ipl_right_; 00019 00020 public: 00021 // parameters 00022 tf::StampedTransform cam_trans; 00023 bool clear_uncolored_points; 00024 00025 CRLib (); 00026 00027 void 00028 setLeftImg (const sensor_msgs::ImageConstPtr &img, 00029 const sensor_msgs::CameraInfoConstPtr &info); 00030 00031 void 00032 setRightImg (const sensor_msgs::ImageConstPtr &img, 00033 const sensor_msgs::CameraInfoConstPtr &info); 00034 00035 bool 00036 calcColor (sensor_msgs::PointCloud &pts, int srwidth, int srheight, 00037 cr_capture::PixelIndices *pidx = NULL); 00038 00039 };