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 <geometry_msgs/PoseWithCovarianceStamped.h>
36 #include <sensor_msgs/CameraInfo.h>
37 #include <sensor_msgs/LaserScan.h>
38 #include <sensor_msgs/Image.h>
39 #include <sensor_msgs/PointCloud2.h>
40 
41 #include <opencv2/opencv.hpp>
42 #include <opencv2/features2d/features2d.hpp>
43 #include <cv_bridge/cv_bridge.h>
44 
45 #include <rtabmap/core/Transform.h>
46 #include <rtabmap/core/Link.h>
47 #include <rtabmap/core/Signature.h>
51 
52 #include <rtabmap_ros/Link.h>
53 #include <rtabmap_ros/KeyPoint.h>
54 #include <rtabmap_ros/Point2f.h>
55 #include <rtabmap_ros/Point3f.h>
56 #include <rtabmap_ros/MapData.h>
57 #include <rtabmap_ros/MapGraph.h>
58 #include <rtabmap_ros/NodeData.h>
59 #include <rtabmap_ros/OdomInfo.h>
60 #include <rtabmap_ros/Info.h>
61 #include <rtabmap_ros/RGBDImage.h>
62 #include <rtabmap_ros/UserData.h>
63 
64 namespace rtabmap_ros {
65 
66 void transformToTF(const rtabmap::Transform & transform, tf::Transform & tfTransform);
68 
69 void transformToGeometryMsg(const rtabmap::Transform & transform, geometry_msgs::Transform & msg);
70 rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform & msg);
71 
72 void transformToPoseMsg(const rtabmap::Transform & transform, geometry_msgs::Pose & msg);
73 rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose & msg, bool ignoreRotationIfNotSet = false);
74 
75 void toCvCopy(const rtabmap_ros::RGBDImage & image, cv_bridge::CvImagePtr & rgb, cv_bridge::CvImagePtr & depth);
76 void toCvShare(const rtabmap_ros::RGBDImageConstPtr & image, cv_bridge::CvImageConstPtr & rgb, cv_bridge::CvImageConstPtr & depth);
77 void rgbdImageToROS(const rtabmap::SensorData & data, rtabmap_ros::RGBDImage & msg, const std::string & sensorFrameId);
78 rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::RGBDImageConstPtr & image);
79 
80 // copy data
81 void compressedMatToBytes(const cv::Mat & compressed, std::vector<unsigned char> & bytes);
82 cv::Mat compressedMatFromBytes(const std::vector<unsigned char> & bytes, bool copy = true);
83 
84 void infoFromROS(const rtabmap_ros::Info & info, rtabmap::Statistics & stat);
85 void infoToROS(const rtabmap::Statistics & stats, rtabmap_ros::Info & info);
86 
87 rtabmap::Link linkFromROS(const rtabmap_ros::Link & msg);
88 void linkToROS(const rtabmap::Link & link, rtabmap_ros::Link & msg);
89 
90 cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint & msg);
91 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
92 
93 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg);
94 void keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg, std::vector<cv::KeyPoint> & kpts, int xShift=0);
95 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_ros::KeyPoint> & msg);
96 
97 rtabmap::GlobalDescriptor globalDescriptorFromROS(const rtabmap_ros::GlobalDescriptor & msg);
98 void globalDescriptorToROS(const rtabmap::GlobalDescriptor & desc, rtabmap_ros::GlobalDescriptor & msg);
99 
100 std::vector<rtabmap::GlobalDescriptor> globalDescriptorsFromROS(const std::vector<rtabmap_ros::GlobalDescriptor> & msg);
101 void globalDescriptorsToROS(const std::vector<rtabmap::GlobalDescriptor> & desc, std::vector<rtabmap_ros::GlobalDescriptor> & msg);
102 
103 rtabmap::EnvSensor envSensorFromROS(const rtabmap_ros::EnvSensor & msg);
104 void envSensorToROS(const rtabmap::EnvSensor & sensor, rtabmap_ros::EnvSensor & msg);
105 rtabmap::EnvSensors envSensorsFromROS(const std::vector<rtabmap_ros::EnvSensor> & msg);
106 void envSensorsToROS(const rtabmap::EnvSensors & sensors, std::vector<rtabmap_ros::EnvSensor> & msg);
107 
108 cv::Point2f point2fFromROS(const rtabmap_ros::Point2f & msg);
109 void point2fToROS(const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
110 
111 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_ros::Point2f> & msg);
112 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_ros::Point2f> & msg);
113 
114 cv::Point3f point3fFromROS(const rtabmap_ros::Point3f & msg);
115 void point3fToROS(const cv::Point3f & pt, rtabmap_ros::Point3f & msg);
116 
117 std::vector<cv::Point3f> points3fFromROS(const std::vector<rtabmap_ros::Point3f> & msg, const rtabmap::Transform & transform = rtabmap::Transform());
118 void points3fFromROS(const std::vector<rtabmap_ros::Point3f> & msg, std::vector<cv::Point3f> & points3, const rtabmap::Transform & transform = rtabmap::Transform());
119 void points3fToROS(const std::vector<cv::Point3f> & pts, std::vector<rtabmap_ros::Point3f> & msg, const rtabmap::Transform & transform = rtabmap::Transform());
120 
122  const sensor_msgs::CameraInfo & camInfo,
123  const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
124 void cameraModelToROS(
125  const rtabmap::CameraModel & model,
126  sensor_msgs::CameraInfo & camInfo);
127 
129  const sensor_msgs::CameraInfo & leftCamInfo,
130  const sensor_msgs::CameraInfo & rightCamInfo,
131  const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity(),
132  const rtabmap::Transform & stereoTransform = rtabmap::Transform());
134  const sensor_msgs::CameraInfo & leftCamInfo,
135  const sensor_msgs::CameraInfo & rightCamInfo,
136  const std::string & frameId,
138  double waitForTransform);
139 
140 void mapDataFromROS(
141  const rtabmap_ros::MapData & msg,
142  std::map<int, rtabmap::Transform> & poses,
143  std::multimap<int, rtabmap::Link> & links,
144  std::map<int, rtabmap::Signature> & signatures,
145  rtabmap::Transform & mapToOdom);
146 void mapDataToROS(
147  const std::map<int, rtabmap::Transform> & poses,
148  const std::multimap<int, rtabmap::Link> & links,
149  const std::map<int, rtabmap::Signature> & signatures,
150  const rtabmap::Transform & mapToOdom,
151  rtabmap_ros::MapData & msg);
152 
153 void mapGraphFromROS(
154  const rtabmap_ros::MapGraph & msg,
155  std::map<int, rtabmap::Transform> & poses,
156  std::multimap<int, rtabmap::Link> & links,
157  rtabmap::Transform & mapToOdom);
158 void mapGraphToROS(
159  const std::map<int, rtabmap::Transform> & poses,
160  const std::multimap<int, rtabmap::Link> & links,
161  const rtabmap::Transform & mapToOdom,
162  rtabmap_ros::MapGraph & msg);
163 
164 rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg);
165 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
166 
167 rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData & msg);
168 void nodeInfoToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
169 
170 std::map<std::string, float> odomInfoToStatistics(const rtabmap::OdometryInfo & info);
171 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo & msg);
172 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_ros::OdomInfo & msg);
173 
174 cv::Mat userDataFromROS(const rtabmap_ros::UserData & dataMsg);
175 void userDataToROS(const cv::Mat & data, rtabmap_ros::UserData & dataMsg, bool compress);
176 
178  const std::map<int, geometry_msgs::PoseWithCovarianceStamped> & tags,
179  const std::string & frameId,
180  const std::string & odomFrameId,
181  const ros::Time & odomStamp,
183  double waitForTransform,
184  double defaultLinVariance,
185  double defaultAngVariance);
186 
187 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
188 
189 // common stuff
191  const std::string & fromFrameId,
192  const std::string & toFrameId,
193  const ros::Time & stamp,
195  double waitForTransform);
196 
197 
198 // get moving transform accordingly to a fixed frame. For example get
199 // transform of /base_link between two stamps accordingly to /odom frame.
201  const std::string & sourceTargetFrame,
202  const std::string & fixedFrame,
203  const ros::Time & stampSource,
204  const ros::Time & stampTarget,
205  tf::TransformListener & listener,
206  double waitForTransform);
207 
208 bool convertRGBDMsgs(
209  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
210  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
211  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
212  const std::string & frameId,
213  const std::string & odomFrameId,
214  const ros::Time & odomStamp,
215  cv::Mat & rgb,
216  cv::Mat & depth,
217  std::vector<rtabmap::CameraModel> & cameraModels,
218  tf::TransformListener & listener,
219  double waitForTransform,
220  const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPointsMsgs = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
221  const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3dMsgs = std::vector<std::vector<rtabmap_ros::Point3f> >(),
222  const std::vector<cv::Mat> & localDescriptorsMsgs = std::vector<cv::Mat>(),
223  std::vector<cv::KeyPoint> * localKeyPoints = 0,
224  std::vector<cv::Point3f> * localPoints3d = 0,
225  cv::Mat * localDescriptors = 0);
226 
227 bool convertStereoMsg(
228  const cv_bridge::CvImageConstPtr& leftImageMsg,
229  const cv_bridge::CvImageConstPtr& rightImageMsg,
230  const sensor_msgs::CameraInfo& leftCamInfoMsg,
231  const sensor_msgs::CameraInfo& rightCamInfoMsg,
232  const std::string & frameId,
233  const std::string & odomFrameId,
234  const ros::Time & odomStamp,
235  cv::Mat & left,
236  cv::Mat & right,
237  rtabmap::StereoCameraModel & stereoModel,
238  tf::TransformListener & listener,
239  double waitForTransform,
240  bool alreadyRectified);
241 
242 bool convertScanMsg(
243  const sensor_msgs::LaserScan & scan2dMsg,
244  const std::string & frameId,
245  const std::string & odomFrameId,
246  const ros::Time & odomStamp,
247  rtabmap::LaserScan & scan,
248  tf::TransformListener & listener,
249  double waitForTransform,
250  bool outputInFrameId = false);
251 
252 bool convertScan3dMsg(
253  const sensor_msgs::PointCloud2 & scan3dMsg,
254  const std::string & frameId,
255  const std::string & odomFrameId,
256  const ros::Time & odomStamp,
257  rtabmap::LaserScan & scan,
258  tf::TransformListener & listener,
259  double waitForTransform,
260  int maxPoints = 0,
261  float maxRange = 0.0f);
262 
263 }
264 
265 #endif /* MSGCONVERSION_H_ */
void globalDescriptorsToROS(const std::vector< rtabmap::GlobalDescriptor > &desc, std::vector< rtabmap_ros::GlobalDescriptor > &msg)
void keypointsToROS(const std::vector< cv::KeyPoint > &kpts, std::vector< rtabmap_ros::KeyPoint > &msg)
rtabmap::Landmarks landmarksFromROS(const std::map< int, geometry_msgs::PoseWithCovarianceStamped > &tags, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, tf::TransformListener &listener, double waitForTransform, double defaultLinVariance, double defaultAngVariance)
void transformToTF(const rtabmap::Transform &transform, tf::Transform &tfTransform)
bool convertScan3dMsg(const sensor_msgs::PointCloud2 &scan3dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, rtabmap::LaserScan &scan, tf::TransformListener &listener, double waitForTransform, int maxPoints=0, float maxRange=0.0f)
rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData &msg)
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_ros::OdomInfo &msg)
rtabmap::EnvSensor envSensorFromROS(const rtabmap_ros::EnvSensor &msg)
f
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)
std::vector< rtabmap::GlobalDescriptor > globalDescriptorsFromROS(const std::vector< rtabmap_ros::GlobalDescriptor > &msg)
static Transform getIdentity()
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
std::map< int, Landmark > Landmarks
rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData &msg)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
void nodeInfoToROS(const rtabmap::Signature &signature, rtabmap_ros::NodeData &msg)
void points3fToROS(const std::vector< cv::Point3f > &pts, std::vector< rtabmap_ros::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform())
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
void point2fToROS(const cv::Point2f &kpt, rtabmap_ros::Point2f &msg)
cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint &msg)
std::map< std::string, float > odomInfoToStatistics(const rtabmap::OdometryInfo &info)
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 rgbdImageToROS(const rtabmap::SensorData &data, rtabmap_ros::RGBDImage &msg, const std::string &sensorFrameId)
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)
void envSensorsToROS(const rtabmap::EnvSensors &sensors, std::vector< rtabmap_ros::EnvSensor > &msg)
std::vector< cv::Point3f > points3fFromROS(const std::vector< rtabmap_ros::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform())
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)
rtabmap::EnvSensors envSensorsFromROS(const std::vector< rtabmap_ros::EnvSensor > &msg)
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
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, const std::vector< std::vector< rtabmap_ros::KeyPoint > > &localKeyPointsMsgs=std::vector< std::vector< rtabmap_ros::KeyPoint > >(), const std::vector< std::vector< rtabmap_ros::Point3f > > &localPoints3dMsgs=std::vector< std::vector< rtabmap_ros::Point3f > >(), const std::vector< cv::Mat > &localDescriptorsMsgs=std::vector< cv::Mat >(), std::vector< cv::KeyPoint > *localKeyPoints=0, std::vector< cv::Point3f > *localPoints3d=0, cv::Mat *localDescriptors=0)
cv::Mat userDataFromROS(const rtabmap_ros::UserData &dataMsg)
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, bool alreadyRectified)
void transformToPoseMsg(const rtabmap::Transform &transform, geometry_msgs::Pose &msg)
string frameId
Definition: patrol.py:11
void keypointToROS(const cv::KeyPoint &kpt, rtabmap_ros::KeyPoint &msg)
bool convertScanMsg(const sensor_msgs::LaserScan &scan2dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, rtabmap::LaserScan &scan, tf::TransformListener &listener, double waitForTransform, bool outputInFrameId=false)
rtabmap::GlobalDescriptor globalDescriptorFromROS(const rtabmap_ros::GlobalDescriptor &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)
void globalDescriptorToROS(const rtabmap::GlobalDescriptor &desc, rtabmap_ros::GlobalDescriptor &msg)
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity(), const rtabmap::Transform &stereoTransform=rtabmap::Transform())
void envSensorToROS(const rtabmap::EnvSensor &sensor, rtabmap_ros::EnvSensor &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)
std::map< EnvSensor::Type, EnvSensor > EnvSensors
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)
void point3fToROS(const cv::Point3f &pt, rtabmap_ros::Point3f &msg)
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 Mon Dec 14 2020 03:42:19