image.cpp
Go to the documentation of this file.
00001 /* +------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)            |
00003    |                          http://www.mrpt.org/                          |
00004    |                                                                        |
00005    | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file     |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                |
00007    | Released under BSD License. See details in http://www.mrpt.org/License |
00008    +------------------------------------------------------------------------+ */
00009 
00010 /*---------------------------------------------------------------
00011         APPLICATION: mrpt_ros bridge
00012         FILE: image.cpp
00013         AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
00014   ---------------------------------------------------------------*/
00015 
00016 #include "ros/ros.h"
00017 #include "mrpt_bridge/image.h"
00018 #include <opencv/highgui.h>
00019 #include <cv_bridge/cv_bridge.h>
00020 
00021 #include <sensor_msgs/Image.h>
00022 #include <sensor_msgs/image_encodings.h>
00023 
00024 #include <mrpt/version.h>
00025 #if MRPT_VERSION>=0x199
00026 using namespace mrpt::img;
00027 #else
00028 using namespace mrpt::utils;
00029 #endif
00030 
00031 using namespace ros;
00032 using namespace sensor_msgs;
00033 using namespace cv;
00034 using namespace cv_bridge;
00035 
00036 
00037 namespace mrpt_bridge
00038 {
00039     namespace image
00040     {
00041         bool ros2mrpt(const sensor_msgs::Image &msg,  CObservationImage &obj)
00042         {
00043             CvImage *frame1 = cv_bridge::toCvCopy(msg, "bgr8").get(); //CvShare(msg,"bgr8").image;
00044             if (!frame1) return false;
00045             IplImage ipl = frame1->image;
00046             obj.image.loadFromIplImage(&ipl);
00047 
00048             return true;
00049         }
00050 
00051         /************************************************************************
00052         *                                               mrpt2ros                                                                *
00053         ************************************************************************/
00054         bool mrpt2ros(const CObservationImage &obj, const std_msgs::Header &msg_header, sensor_msgs::Image &msg)
00055         {
00056             CImage temp_img = obj.image;
00057             Mat cvImg = cv::cvarrToMat(temp_img.getAs<IplImage>());
00058 
00059             cv_bridge::CvImage img_bridge;
00060             sensor_msgs::Image img_msg;
00061 
00062             img_bridge = CvImage(msg.header, sensor_msgs::image_encodings::BGR8, cvImg);
00063             img_bridge.toImageMsg(msg);
00064 
00065             msg.encoding = "bgr8";
00066             msg.header = msg_header;
00067             msg.height = (int) obj.image.getHeight();
00068             msg.width = (int) obj.image.getWidth();
00069 
00070             return true;
00071         }
00072     }
00073 }
00074 
00075 //
00076 /*
00077 std_msgs/Header header
00078 uint32 height
00079 uint32 width
00080 string encoding
00081 uint8 is_bigendian
00082 uint32 step
00083 uint8[] data
00084  */


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Apr 27 2018 05:10:54