Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #include "cv_bridge/CvBridge.h" 
00031 #include "opencv/cxcore.h" 
00032 #include "opencv/cv.h" 
00033 #include "opencv/highgui.h" 
00034 #include "ros/node_handle.h"
00035 #include "sensor_msgs/Image.h"
00036 
00037 
00038 
00039 class DisparityViewer
00040 {
00041 private:
00042   
00043   sensor_msgs::ImageConstPtr left_image_ptr_;
00044   sensor_msgs::ImageConstPtr disparity_image_ptr_;
00045   
00046   
00047   sensor_msgs::CvBridge left_bridge_;
00048   sensor_msgs::CvBridge disparity_bridge_;
00049   
00050   
00051   ros::NodeHandle nh_;
00052   ros::Subscriber left_image_sub_;
00053   ros::Subscriber disparity_image_sub_;
00054   
00055   
00056   
00057   
00058   
00059 public:
00060   DisparityViewer(const ros::NodeHandle& node_handle)
00061     : nh_(node_handle)
00062   {
00063     
00064     cvNamedWindow("Left");
00065     cvNamedWindow("Disparity");
00066     
00067     
00068     
00069     
00070     left_image_sub_ = nh_.subscribe("/stereo/left/image", 1, &DisparityViewer::leftImageCallback,this );
00071     disparity_image_sub_ = nh_.subscribe("/stereo/disparity", 1, &DisparityViewer::disparityImageCallback,this );
00072   }
00073   
00074   ~DisparityViewer()
00075   {
00076     
00077     cvDestroyWindow("Left");
00078     cvDestroyWindow("Disparity");
00079   }
00080   
00081   
00082   void leftImageCallback(const sensor_msgs::ImageConstPtr& image_ptr)
00083   {
00084     IplImage *left_iplimage;
00085     
00086     left_image_ptr_ =  image_ptr;
00087     if (left_bridge_.fromImage(*left_image_ptr_)) {
00088       ROS_INFO("left image\n");
00089       left_iplimage = left_bridge_.toIpl();
00090     }
00091     else {
00092       ROS_INFO("no left image\n");
00093       return;
00094     }
00095 
00096     
00097     cvShowImage("Left", left_iplimage);
00098 
00099     cvWaitKey(2);
00100   }
00101   
00102   
00103   void disparityImageCallback(const sensor_msgs::ImageConstPtr& image_ptr)
00104   {
00105     IplImage *disparity_iplimage;
00106     
00107     disparity_image_ptr_ = image_ptr;
00108 
00109     if (disparity_bridge_.fromImage(*disparity_image_ptr_)) {
00110       ROS_INFO("disp image\n");
00111       disparity_iplimage = disparity_bridge_.toIpl();
00112     }
00113     else {
00114       ROS_INFO("no disp image\n");
00115       return;
00116     }
00117     
00118     
00119     IplImage *disparity_out = cvCreateImage(cvGetSize(disparity_iplimage), IPL_DEPTH_8U, 1);
00120     cvCvtScale(disparity_iplimage, disparity_out, 4.0/16.0);
00121     cvShowImage("Disparity", disparity_out);
00122     
00123     
00124     cvReleaseImage(&disparity_out);
00125 
00126     cvWaitKey(4);
00127   }
00128   
00129   
00130   void imageCallback()
00131   {
00132     IplImage *left_iplimage, *disparity_iplimage;
00133 
00134     
00135     
00136     
00137     
00138     if (left_bridge_.fromImage(*left_image_ptr_,"bgr") && disparity_bridge_.fromImage(*disparity_image_ptr_)) {
00139       left_iplimage = left_bridge_.toIpl();
00140       disparity_iplimage = disparity_bridge_.toIpl();
00141     }
00142     else {
00143       return;
00144     }
00145     
00146     
00147     cvShowImage("Left", left_iplimage);
00148     
00149     
00150     IplImage *disparity_out = cvCreateImage(cvGetSize(disparity_iplimage), IPL_DEPTH_8U, 1);
00151     cvCvtScale(disparity_iplimage, disparity_out, 4.0/16.0);
00152     cvShowImage("Disparity", disparity_iplimage);
00153     
00154     cvWaitKey(2);
00155     
00156     cvReleaseImage(&disparity_out);
00157   }
00158   
00159 };  
00160 
00161 int main(int argc, char **argv)
00162 {
00163   
00164 
00165   ros::init(argc, argv, "disparity_viewer");
00166   ros::NodeHandle n;
00167   DisparityViewer viewer(n);
00168   ros::spin();
00169   return 0;
00170 }
00171 
00172