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 <mrpt/utils.h>
00019 #include <opencv/highgui.h>
00020 #include <cv_bridge/cv_bridge.h>
00021 
00022 #include <sensor_msgs/Image.h>
00023 #include <sensor_msgs/image_encodings.h>
00024 
00025 using namespace ros;
00026 using namespace sensor_msgs;
00027 using namespace cv;
00028 using namespace mrpt::utils;
00029 using namespace cv_bridge;
00030 
00031 
00032 namespace mrpt_bridge
00033 {
00034     namespace image
00035     {
00036         bool ros2mrpt(const sensor_msgs::Image &msg,  CObservationImage &obj)
00037         {
00038             CvImage *frame1 = cv_bridge::toCvCopy(msg, "bgr8").get(); //CvShare(msg,"bgr8").image;
00039 
00040         }
00041 
00042         /************************************************************************
00043         *                                               mrpt2ros                                                                *
00044         ************************************************************************/
00045         bool mrpt2ros(const CObservationImage &obj, const std_msgs::Header &msg_header, sensor_msgs::Image &msg)
00046         {
00047             CImage temp_img = obj.image;
00048             Mat cvImg = cv::cvarrToMat(temp_img.getAs<IplImage>());
00049 
00050             cv_bridge::CvImage img_bridge;
00051             sensor_msgs::Image img_msg;
00052 
00053             img_bridge = CvImage(msg.header, sensor_msgs::image_encodings::BGR8, cvImg);
00054             img_bridge.toImageMsg(msg);
00055 
00056             msg.encoding = "bgr8";
00057             msg.header = msg_header;
00058             msg.height = (int) obj.image.getHeight();
00059             msg.width = (int) obj.image.getWidth();
00060 
00061             return true;
00062         }
00063     }
00064 }
00065 
00066 //
00067 /*
00068 std_msgs/Header header
00069 uint32 height
00070 uint32 width
00071 string encoding
00072 uint8 is_bigendian
00073 uint32 step
00074 uint8[] data
00075  */


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06