MsgConversion.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef MSGCONVERSION_H_
29 #define MSGCONVERSION_H_
30 
31 #include <tf/tf.h>
32 #include <tf/transform_listener.h>
33 #include <geometry_msgs/Transform.h>
34 #include <geometry_msgs/Pose.h>
35 #include <sensor_msgs/CameraInfo.h>
36 #include <sensor_msgs/LaserScan.h>
37 #include <sensor_msgs/Image.h>
38 
39 #include <opencv2/opencv.hpp>
40 #include <opencv2/features2d/features2d.hpp>
41 #include <cv_bridge/cv_bridge.h>
42 
43 #include <rtabmap/core/Transform.h>
44 #include <rtabmap/core/Link.h>
45 #include <rtabmap/core/Signature.h>
49 
50 #include <rtabmap_ros/Link.h>
51 #include <rtabmap_ros/KeyPoint.h>
52 #include <rtabmap_ros/Point2f.h>
53 #include <rtabmap_ros/Point3f.h>
54 #include <rtabmap_ros/MapData.h>
55 #include <rtabmap_ros/MapGraph.h>
56 #include <rtabmap_ros/NodeData.h>
57 #include <rtabmap_ros/OdomInfo.h>
58 #include <rtabmap_ros/Info.h>
59 #include <rtabmap_ros/RGBDImage.h>
60 #include <rtabmap_ros/UserData.h>
61 
62 namespace rtabmap_ros {
63 
64 void transformToTF(const rtabmap::Transform & transform, tf::Transform & tfTransform);
66 
67 void transformToGeometryMsg(const rtabmap::Transform & transform, geometry_msgs::Transform & msg);
68 rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform & msg);
69 
70 void transformToPoseMsg(const rtabmap::Transform & transform, geometry_msgs::Pose & msg);
71 rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose & msg);
72 
73 void toCvCopy(const rtabmap_ros::RGBDImage & image, cv_bridge::CvImagePtr & rgb, cv_bridge::CvImagePtr & depth);
74 void toCvShare(const rtabmap_ros::RGBDImageConstPtr & image, cv_bridge::CvImageConstPtr & rgb, cv_bridge::CvImageConstPtr & depth);
75 rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::RGBDImageConstPtr & image);
76 
77 // copy data
78 void compressedMatToBytes(const cv::Mat & compressed, std::vector<unsigned char> & bytes);
79 cv::Mat compressedMatFromBytes(const std::vector<unsigned char> & bytes, bool copy = true);
80 
81 void infoFromROS(const rtabmap_ros::Info & info, rtabmap::Statistics & stat);
82 void infoToROS(const rtabmap::Statistics & stats, rtabmap_ros::Info & info);
83 
84 rtabmap::Link linkFromROS(const rtabmap_ros::Link & msg);
85 void linkToROS(const rtabmap::Link & link, rtabmap_ros::Link & msg);
86 
87 cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint & msg);
88 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
89 
90 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg);
91 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_ros::KeyPoint> & msg);
92 
93 cv::Point2f point2fFromROS(const rtabmap_ros::Point2f & msg);
94 void point2fToROS(const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
95 
96 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_ros::Point2f> & msg);
97 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_ros::Point2f> & msg);
98 
99 cv::Point3f point3fFromROS(const rtabmap_ros::Point3f & msg);
100 void point3fToROS(const cv::Point3f & kpt, rtabmap_ros::Point3f & msg);
101 
102 std::vector<cv::Point3f> points3fFromROS(const std::vector<rtabmap_ros::Point3f> & msg);
103 void points3fToROS(const std::vector<cv::Point3f> & kpts, std::vector<rtabmap_ros::Point3f> & msg);
104 
106  const sensor_msgs::CameraInfo & camInfo,
107  const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
108 void cameraModelToROS(
109  const rtabmap::CameraModel & model,
110  sensor_msgs::CameraInfo & camInfo);
111 
113  const sensor_msgs::CameraInfo & leftCamInfo,
114  const sensor_msgs::CameraInfo & rightCamInfo,
115  const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
116 
117 void mapDataFromROS(
118  const rtabmap_ros::MapData & msg,
119  std::map<int, rtabmap::Transform> & poses,
120  std::multimap<int, rtabmap::Link> & links,
121  std::map<int, rtabmap::Signature> & signatures,
122  rtabmap::Transform & mapToOdom);
123 void mapDataToROS(
124  const std::map<int, rtabmap::Transform> & poses,
125  const std::multimap<int, rtabmap::Link> & links,
126  const std::map<int, rtabmap::Signature> & signatures,
127  const rtabmap::Transform & mapToOdom,
128  rtabmap_ros::MapData & msg);
129 
130 void mapGraphFromROS(
131  const rtabmap_ros::MapGraph & msg,
132  std::map<int, rtabmap::Transform> & poses,
133  std::multimap<int, rtabmap::Link> & links,
134  rtabmap::Transform & mapToOdom);
135 void mapGraphToROS(
136  const std::map<int, rtabmap::Transform> & poses,
137  const std::multimap<int, rtabmap::Link> & links,
138  const rtabmap::Transform & mapToOdom,
139  rtabmap_ros::MapGraph & msg);
140 
141 rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg);
142 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
143 
144 rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData & msg);
145 void nodeInfoToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
146 
147 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo & msg);
148 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_ros::OdomInfo & msg);
149 
150 cv::Mat userDataFromROS(const rtabmap_ros::UserData & dataMsg);
151 void userDataToROS(const cv::Mat & data, rtabmap_ros::UserData & dataMsg, bool compress);
152 
153 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
154 
155 // common stuff
157  const std::string & fromFrameId,
158  const std::string & toFrameId,
159  const ros::Time & stamp,
161  double waitForTransform);
162 
163 
164 // get moving transform accordingly to a fixed frame. For example get
165 // transform of /base_link between two stamps accordingly to /odom frame.
167  const std::string & sourceTargetFrame,
168  const std::string & fixedFrame,
169  const ros::Time & stampSource,
170  const ros::Time & stampTarget,
171  tf::TransformListener & listener,
172  double waitForTransform);
173 
174 bool convertRGBDMsgs(
175  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
176  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
177  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
178  const std::string & frameId,
179  const std::string & odomFrameId,
180  const ros::Time & odomStamp,
181  cv::Mat & rgb,
182  cv::Mat & depth,
183  std::vector<rtabmap::CameraModel> & cameraModels,
184  tf::TransformListener & listener,
185  double waitForTransform);
186 
187 bool convertStereoMsg(
188  const cv_bridge::CvImageConstPtr& leftImageMsg,
189  const cv_bridge::CvImageConstPtr& rightImageMsg,
190  const sensor_msgs::CameraInfo& leftCamInfoMsg,
191  const sensor_msgs::CameraInfo& rightCamInfoMsg,
192  const std::string & frameId,
193  const std::string & odomFrameId,
194  const ros::Time & odomStamp,
195  cv::Mat & left,
196  cv::Mat & right,
197  rtabmap::StereoCameraModel & stereoModel,
198  tf::TransformListener & listener,
199  double waitForTransform);
200 
201 bool convertScanMsg(
202  const sensor_msgs::LaserScanConstPtr& scan2dMsg,
203  const std::string & frameId,
204  const std::string & odomFrameId,
205  const ros::Time & odomStamp,
206  cv::Mat & scan,
207  rtabmap::Transform & scanLocalTransform,
208  tf::TransformListener & listener,
209  double waitForTransform);
210 
211 bool convertScan3dMsg(
212  const sensor_msgs::PointCloud2ConstPtr & scan3dMsg,
213  const std::string & frameId,
214  const std::string & odomFrameId,
215  const ros::Time & odomStamp,
216  cv::Mat & scan,
217  rtabmap::Transform & scanLocalTransform,
218  tf::TransformListener & listener,
219  double waitForTransform);
220 
221 }
222 
223 #endif /* MSGCONVERSION_H_ */
bool convertScanMsg(const sensor_msgs::LaserScanConstPtr &scan2dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &scan, rtabmap::Transform &scanLocalTransform, tf::TransformListener &listener, double waitForTransform)
void keypointsToROS(const std::vector< cv::KeyPoint > &kpts, std::vector< rtabmap_ros::KeyPoint > &msg)
void transformToTF(const rtabmap::Transform &transform, tf::Transform &tfTransform)
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData &msg)
bool convertScan3dMsg(const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &scan, rtabmap::Transform &scanLocalTransform, tf::TransformListener &listener, double waitForTransform)
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_ros::OdomInfo &msg)
void points2fToROS(const std::vector< cv::Point2f > &kpts, std::vector< rtabmap_ros::Point2f > &msg)
rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::RGBDImageConstPtr &image)
void mapGraphToROS(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const rtabmap::Transform &mapToOdom, rtabmap_ros::MapGraph &msg)
rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo &msg)
static Transform getIdentity()
std::vector< cv::Point3f > points3fFromROS(const std::vector< rtabmap_ros::Point3f > &msg)
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData &msg)
void nodeInfoToROS(const rtabmap::Signature &signature, rtabmap_ros::NodeData &msg)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
void points3fToROS(const std::vector< cv::Point3f > &kpts, std::vector< rtabmap_ros::Point3f > &msg)
void point2fToROS(const cv::Point2f &kpt, rtabmap_ros::Point2f &msg)
cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint &msg)
void mapDataFromROS(const rtabmap_ros::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
void linkToROS(const rtabmap::Link &link, rtabmap_ros::Link &msg)
rtabmap::Link linkFromROS(const rtabmap_ros::Link &msg)
void point3fToROS(const cv::Point3f &kpt, rtabmap_ros::Point3f &msg)
void mapDataToROS(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const std::map< int, rtabmap::Signature > &signatures, const rtabmap::Transform &mapToOdom, rtabmap_ros::MapData &msg)
cv::Point3f point3fFromROS(const rtabmap_ros::Point3f &msg)
void infoFromROS(const rtabmap_ros::Info &info, rtabmap::Statistics &stat)
void mapGraphFromROS(const rtabmap_ros::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
cv::Mat compressedMatFromBytes(const std::vector< unsigned char > &bytes, bool copy=true)
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
std::vector< cv::KeyPoint > keypointsFromROS(const std::vector< rtabmap_ros::KeyPoint > &msg)
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
bool convertStereoMsg(const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &left, cv::Mat &right, rtabmap::StereoCameraModel &stereoModel, tf::TransformListener &listener, double waitForTransform)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg)
cv::Mat userDataFromROS(const rtabmap_ros::UserData &dataMsg)
void transformToPoseMsg(const rtabmap::Transform &transform, geometry_msgs::Pose &msg)
void keypointToROS(const cv::KeyPoint &kpt, rtabmap_ros::KeyPoint &msg)
void toCvShare(const rtabmap_ros::RGBDImageConstPtr &image, cv_bridge::CvImageConstPtr &rgb, cv_bridge::CvImageConstPtr &depth)
std::vector< cv::Point2f > points2fFromROS(const std::vector< rtabmap_ros::Point2f > &msg)
double timestampFromROS(const ros::Time &stamp)
void toCvCopy(const rtabmap_ros::RGBDImage &image, cv_bridge::CvImagePtr &rgb, cv_bridge::CvImagePtr &depth)
void userDataToROS(const cv::Mat &data, rtabmap_ros::UserData &dataMsg, bool compress)
void compressedMatToBytes(const cv::Mat &compressed, std::vector< unsigned char > &bytes)
rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform &msg)
void nodeDataToROS(const rtabmap::Signature &signature, rtabmap_ros::NodeData &msg)
rtabmap::Transform transformFromTF(const tf::Transform &transform)
bool convertRGBDMsgs(const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &rgb, cv::Mat &depth, std::vector< rtabmap::CameraModel > &cameraModels, tf::TransformListener &listener, double waitForTransform)
cv::Point2f point2fFromROS(const rtabmap_ros::Point2f &msg)
void infoToROS(const rtabmap::Statistics &stats, rtabmap_ros::Info &info)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04