image.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 /*---------------------------------------------------------------
11  APPLICATION: mrpt_ros bridge
12  FILE: image.cpp
13  AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
14  ---------------------------------------------------------------*/
15 
16 #include "ros/ros.h"
17 #include "mrpt_bridge/image.h"
18 #include <opencv2/highgui.hpp>
19 #include <cv_bridge/cv_bridge.h>
20 #include <sensor_msgs/Image.h>
22 #include <mrpt/ros1bridge/time.h>
23 #include <mrpt/ros1bridge/image.h>
24 
25 using namespace mrpt::img;
26 using namespace ros;
27 using namespace sensor_msgs;
28 using namespace cv;
29 using namespace cv_bridge;
30 
32  const sensor_msgs::Image& msg, mrpt::obs::CObservationImage& obj)
33 {
34  obj.timestamp = mrpt::ros1bridge::fromROS(msg.header.stamp);
35  obj.image = mrpt::ros1bridge::fromROS(msg);
36  return true;
37 }
38 
40  const mrpt::obs::CObservationImage& obj, const std_msgs::Header& msg_header,
41  sensor_msgs::Image& msg)
42 {
43  msg = mrpt::ros1bridge::toROS(obj.image, msg_header);
44  return true;
45 }
46 
47 //
48 /*
49 std_msgs/Header header
50 uint32 height
51 uint32 width
52 string encoding
53 uint8 is_bigendian
54 uint32 step
55 uint8[] data
56  */
bool ros2mrpt(const sensor_msgs::Image &msg, mrpt::obs::CObservationImage &obj)
Definition: image.cpp:31
bool mrpt2ros(const mrpt::obs::CObservationImage &obj, const std_msgs::Header &msg_header, sensor_msgs::Image &msg)
Definition: image.cpp:39


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Thu May 12 2022 02:26:47