19 #include <opencv/highgui.h>
22 #include <sensor_msgs/Image.h>
25 #include <mrpt/version.h>
26 #if MRPT_VERSION >= 0x199
27 using namespace mrpt::img;
39 namespace stereo_image
53 sensor_msgs::Image& left, sensor_msgs::Image& right,
54 stereo_msgs::DisparityImage& disparity)
57 CImage temp_img = obj.imageLeft;
58 #if MRPT_VERSION>=0x199
59 Mat cvImg = temp_img.asCvMatRef();
61 Mat cvImg = cv::cvarrToMat(temp_img.getAs<IplImage>());
67 left.encoding =
"bgr8";
68 left.header = msg_header;
69 left.height = (int)obj.imageLeft.getHeight();
70 left.width = (int)obj.imageRight.getWidth();
73 CImage temp_img2 = obj.imageRight;
74 #if MRPT_VERSION>=0x199
75 Mat cvImg2 = temp_img2.asCvMatRef();
77 Mat cvImg2 = cv::cvarrToMat(temp_img2.getAs<IplImage>());
83 right.encoding =
"bgr8";
84 right.header = msg_header;
85 right.height = (int)obj.imageLeft.getHeight();
86 right.width = (int)obj.imageRight.getWidth();
88 if (obj.hasImageDisparity)
90 CImage temp_disp = obj.imageDisparity;
91 #if MRPT_VERSION>=0x199
92 Mat cvImg3 = temp_disp.asCvMatRef();
94 Mat cvImg3 = cv::cvarrToMat(temp_disp.getAs<IplImage>());
100 disparity.image.encoding =
"bgr8";
101 disparity.image.header = msg_header;
102 disparity.image.height = (int)obj.imageDisparity.getHeight();
103 disparity.image.width = (int)obj.imageDisparity.getWidth();