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_msgs/Link.h>
53 #include <rtabmap_msgs/KeyPoint.h>
54 #include <rtabmap_msgs/Point2f.h>
55 #include <rtabmap_msgs/Point3f.h>
56 #include <rtabmap_msgs/MapData.h>
57 #include <rtabmap_msgs/MapGraph.h>
58 #include <rtabmap_msgs/Node.h>
59 #include <rtabmap_msgs/OdomInfo.h>
60 #include <rtabmap_msgs/Info.h>
61 #include <rtabmap_msgs/RGBDImage.h>
62 #include <rtabmap_msgs/UserData.h>
63 
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_msgs::RGBDImage & image, cv_bridge::CvImagePtr & rgb, cv_bridge::CvImagePtr & depth);
76 void toCvShare(const rtabmap_msgs::RGBDImageConstPtr & image, cv_bridge::CvImageConstPtr & rgb, cv_bridge::CvImageConstPtr & depth);
77 void toCvShare(const rtabmap_msgs::RGBDImage & image, const boost::shared_ptr<void const>& trackedObject, cv_bridge::CvImageConstPtr & rgb, cv_bridge::CvImageConstPtr & depth);
78 void rgbdImageToROS(const rtabmap::SensorData & data, rtabmap_msgs::RGBDImage & msg, const std::string & sensorFrameId);
79 rtabmap::SensorData rgbdImageFromROS(const rtabmap_msgs::RGBDImageConstPtr & image);
80 
81 // copy data
82 void compressedMatToBytes(const cv::Mat & compressed, std::vector<unsigned char> & bytes);
83 cv::Mat compressedMatFromBytes(const std::vector<unsigned char> & bytes, bool copy = true);
84 
85 void infoFromROS(const rtabmap_msgs::Info & info, rtabmap::Statistics & stat);
86 void infoToROS(const rtabmap::Statistics & stats, rtabmap_msgs::Info & info);
87 
88 rtabmap::Link linkFromROS(const rtabmap_msgs::Link & msg);
89 void linkToROS(const rtabmap::Link & link, rtabmap_msgs::Link & msg);
90 
91 cv::KeyPoint keypointFromROS(const rtabmap_msgs::KeyPoint & msg);
92 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_msgs::KeyPoint & msg);
93 
94 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_msgs::KeyPoint> & msg);
95 void keypointsFromROS(const std::vector<rtabmap_msgs::KeyPoint> & msg, std::vector<cv::KeyPoint> & kpts, int xShift=0);
96 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_msgs::KeyPoint> & msg);
97 
98 rtabmap::GlobalDescriptor globalDescriptorFromROS(const rtabmap_msgs::GlobalDescriptor & msg);
99 void globalDescriptorToROS(const rtabmap::GlobalDescriptor & desc, rtabmap_msgs::GlobalDescriptor & msg);
100 
101 std::vector<rtabmap::GlobalDescriptor> globalDescriptorsFromROS(const std::vector<rtabmap_msgs::GlobalDescriptor> & msg);
102 void globalDescriptorsToROS(const std::vector<rtabmap::GlobalDescriptor> & desc, std::vector<rtabmap_msgs::GlobalDescriptor> & msg);
103 
104 rtabmap::EnvSensor envSensorFromROS(const rtabmap_msgs::EnvSensor & msg);
105 void envSensorToROS(const rtabmap::EnvSensor & sensor, rtabmap_msgs::EnvSensor & msg);
106 rtabmap::EnvSensors envSensorsFromROS(const std::vector<rtabmap_msgs::EnvSensor> & msg);
107 void envSensorsToROS(const rtabmap::EnvSensors & sensors, std::vector<rtabmap_msgs::EnvSensor> & msg);
108 
109 cv::Point2f point2fFromROS(const rtabmap_msgs::Point2f & msg);
110 void point2fToROS(const cv::Point2f & kpt, rtabmap_msgs::Point2f & msg);
111 
112 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_msgs::Point2f> & msg);
113 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_msgs::Point2f> & msg);
114 
115 cv::Point3f point3fFromROS(const rtabmap_msgs::Point3f & msg);
116 void point3fToROS(const cv::Point3f & pt, rtabmap_msgs::Point3f & msg);
117 
118 std::vector<cv::Point3f> points3fFromROS(const std::vector<rtabmap_msgs::Point3f> & msg, const rtabmap::Transform & transform = rtabmap::Transform());
119 void points3fFromROS(const std::vector<rtabmap_msgs::Point3f> & msg, std::vector<cv::Point3f> & points3, const rtabmap::Transform & transform = rtabmap::Transform());
120 void points3fToROS(const std::vector<cv::Point3f> & pts, std::vector<rtabmap_msgs::Point3f> & msg, const rtabmap::Transform & transform = rtabmap::Transform());
121 
123  const sensor_msgs::CameraInfo & camInfo,
124  const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
125 void cameraModelToROS(
126  const rtabmap::CameraModel & model,
127  sensor_msgs::CameraInfo & camInfo);
128 
130  const sensor_msgs::CameraInfo & leftCamInfo,
131  const sensor_msgs::CameraInfo & rightCamInfo,
132  const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity(),
133  const rtabmap::Transform & stereoTransform = rtabmap::Transform());
135  const sensor_msgs::CameraInfo & leftCamInfo,
136  const sensor_msgs::CameraInfo & rightCamInfo,
137  const std::string & frameId,
138  tf::TransformListener & listener,
139  double waitForTransform);
140 
141 void mapDataFromROS(
142  const rtabmap_msgs::MapData & msg,
143  std::map<int, rtabmap::Transform> & poses,
144  std::multimap<int, rtabmap::Link> & links,
145  std::map<int, rtabmap::Signature> & signatures,
146  rtabmap::Transform & mapToOdom);
147 void mapDataToROS(
148  const std::map<int, rtabmap::Transform> & poses,
149  const std::multimap<int, rtabmap::Link> & links,
150  const std::map<int, rtabmap::Signature> & signatures,
151  const rtabmap::Transform & mapToOdom,
152  rtabmap_msgs::MapData & msg);
153 
154 void mapGraphFromROS(
155  const rtabmap_msgs::MapGraph & msg,
156  std::map<int, rtabmap::Transform> & poses,
157  std::multimap<int, rtabmap::Link> & links,
158  rtabmap::Transform & mapToOdom);
159 void mapGraphToROS(
160  const std::map<int, rtabmap::Transform> & poses,
161  const std::multimap<int, rtabmap::Link> & links,
162  const rtabmap::Transform & mapToOdom,
163  rtabmap_msgs::MapGraph & msg);
164 
165 rtabmap::SensorData sensorDataFromROS(const rtabmap_msgs::SensorData & msg);
166 void sensorDataToROS(const rtabmap::SensorData & signature, rtabmap_msgs::SensorData & msg, const std::string & frameId = "base_link", bool copyRawData = false);
167 
168 rtabmap::Signature nodeFromROS(const rtabmap_msgs::Node & msg);
169 void nodeToROS(const rtabmap::Signature & signature, rtabmap_msgs::Node & msg);
170 
171 // DEPRECATED
172 rtabmap::Signature nodeDataFromROS(const rtabmap_msgs::Node & msg);
173 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_msgs::Node & msg);
174 
175 rtabmap::Signature nodeInfoFromROS(const rtabmap_msgs::Node & msg);
176 void nodeInfoToROS(const rtabmap::Signature & signature, rtabmap_msgs::Node & msg);
177 
178 std::map<std::string, float> odomInfoToStatistics(const rtabmap::OdometryInfo & info);
179 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_msgs::OdomInfo & msg, bool ignoreData = false);
180 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_msgs::OdomInfo & msg, bool ignoreData = false);
181 
182 cv::Mat userDataFromROS(const rtabmap_msgs::UserData & dataMsg);
183 void userDataToROS(const cv::Mat & data, rtabmap_msgs::UserData & dataMsg, bool compress);
184 
185 rtabmap::IMU imuFromROS(const sensor_msgs::Imu & msg, const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
186 void imuToROS(const rtabmap::IMU & imu, sensor_msgs::Imu & msg);
187 
189  const std::map<int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> > & tags,
190  const std::string & frameId,
191  const std::string & odomFrameId,
192  const ros::Time & odomStamp,
193  tf::TransformListener & listener,
194  double waitForTransform,
195  double defaultLinVariance,
196  double defaultAngVariance);
197 
198 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
199 
200 // common stuff
202  const std::string & fromFrameId,
203  const std::string & toFrameId,
204  const ros::Time & stamp,
205  tf::TransformListener & listener,
206  double waitForTransform);
207 
208 
209 // get moving transform accordingly to a fixed frame. For example get
210 // transform of /base_link between two stamps accordingly to /odom frame.
212  const std::string & movingFrame,
213  const std::string & fixedFrame,
214  const ros::Time & stampFrom,
215  const ros::Time & stampTo,
216  tf::TransformListener & listener,
217  double waitForTransform);
218 
219 bool convertRGBDMsgs(
220  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
221  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
222  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
223  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
224  const std::string & frameId,
225  const std::string & odomFrameId,
226  const ros::Time & odomStamp,
227  cv::Mat & rgb,
228  cv::Mat & depth,
229  std::vector<rtabmap::CameraModel> & cameraModels,
230  std::vector<rtabmap::StereoCameraModel> & stereoCameraModels,
231  tf::TransformListener & listener,
232  double waitForTransform,
233  bool alreadRectifiedImages,
234  const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPointsMsgs = std::vector<std::vector<rtabmap_msgs::KeyPoint> >(),
235  const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3dMsgs = std::vector<std::vector<rtabmap_msgs::Point3f> >(),
236  const std::vector<cv::Mat> & localDescriptorsMsgs = std::vector<cv::Mat>(),
237  std::vector<cv::KeyPoint> * localKeyPoints = 0,
238  std::vector<cv::Point3f> * localPoints3d = 0,
239  cv::Mat * localDescriptors = 0);
240 
241 bool convertStereoMsg(
242  const cv_bridge::CvImageConstPtr& leftImageMsg,
243  const cv_bridge::CvImageConstPtr& rightImageMsg,
244  const sensor_msgs::CameraInfo& leftCamInfoMsg,
245  const sensor_msgs::CameraInfo& rightCamInfoMsg,
246  const std::string & frameId,
247  const std::string & odomFrameId,
248  const ros::Time & odomStamp,
249  cv::Mat & left,
250  cv::Mat & right,
251  rtabmap::StereoCameraModel & stereoModel,
252  tf::TransformListener & listener,
253  double waitForTransform,
254  bool alreadyRectified);
255 
256 bool convertScanMsg(
257  const sensor_msgs::LaserScan & scan2dMsg,
258  const std::string & frameId,
259  const std::string & odomFrameId,
260  const ros::Time & odomStamp,
261  rtabmap::LaserScan & scan,
262  tf::TransformListener & listener,
263  double waitForTransform,
264  bool outputInFrameId = false);
265 
266 bool convertScan3dMsg(
267  const sensor_msgs::PointCloud2 & scan3dMsg,
268  const std::string & frameId,
269  const std::string & odomFrameId,
270  const ros::Time & odomStamp,
271  rtabmap::LaserScan & scan,
272  tf::TransformListener & listener,
273  double waitForTransform,
274  int maxPoints = 0,
275  float maxRange = 0.0f,
276  bool is2D = false);
277 
278 bool deskew(
279  const sensor_msgs::PointCloud2 & input,
280  sensor_msgs::PointCloud2 & output,
281  const std::string & fixedFrameId,
282  tf::TransformListener & listener,
283  double waitForTransform,
284  bool slerp = false);
285 
286 bool deskew(
287  const sensor_msgs::PointCloud2 & input,
288  sensor_msgs::PointCloud2 & output,
289  double previousStamp,
290  const rtabmap::Transform & velocity);
291 
292 }
293 
294 #endif /* MSGCONVERSION_H_ */
rtabmap::SensorData
rtabmap_conversions::convertScanMsg
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)
Definition: MsgConversion.cpp:2592
rtabmap_conversions::transformToTF
void transformToTF(const rtabmap::Transform &transform, tf::Transform &tfTransform)
Definition: MsgConversion.cpp:52
rtabmap_conversions::transformFromGeometryMsg
rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform &msg)
Definition: MsgConversion.cpp:91
rtabmap_conversions::nodeFromROS
rtabmap::Signature nodeFromROS(const rtabmap_msgs::Node &msg)
Definition: MsgConversion.cpp:1399
rtabmap_conversions::point3fToROS
void point3fToROS(const cv::Point3f &pt, rtabmap_msgs::Point3f &msg)
Definition: MsgConversion.cpp:740
rtabmap_conversions::globalDescriptorsToROS
void globalDescriptorsToROS(const std::vector< rtabmap::GlobalDescriptor > &desc, std::vector< rtabmap_msgs::GlobalDescriptor > &msg)
Definition: MsgConversion.cpp:652
rtabmap_conversions::deskew
bool deskew(const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud2 &output, const std::string &fixedFrameId, tf::TransformListener &listener, double waitForTransform, bool slerp=false)
Definition: MsgConversion.cpp:3395
rtabmap::StereoCameraModel
rtabmap_conversions::toCvShare
void toCvShare(const rtabmap_msgs::RGBDImageConstPtr &image, cv_bridge::CvImageConstPtr &rgb, cv_bridge::CvImageConstPtr &depth)
Definition: MsgConversion.cpp:166
rtabmap_conversions::mapGraphToROS
void mapGraphToROS(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const rtabmap::Transform &mapToOdom, rtabmap_msgs::MapGraph &msg)
Definition: MsgConversion.cpp:1033
rtabmap::Statistics
rtabmap_conversions::globalDescriptorsFromROS
std::vector< rtabmap::GlobalDescriptor > globalDescriptorsFromROS(const std::vector< rtabmap_msgs::GlobalDescriptor > &msg)
Definition: MsgConversion.cpp:638
rtabmap_conversions::globalDescriptorFromROS
rtabmap::GlobalDescriptor globalDescriptorFromROS(const rtabmap_msgs::GlobalDescriptor &msg)
Definition: MsgConversion.cpp:626
bytes
rtabmap_conversions::points2fToROS
void points2fToROS(const std::vector< cv::Point2f > &kpts, std::vector< rtabmap_msgs::Point2f > &msg)
Definition: MsgConversion.cpp:726
boost::shared_ptr
rtabmap_conversions::getTransform
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
Definition: MsgConversion.cpp:1971
rtabmap_conversions::transformFromPoseMsg
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
Definition: MsgConversion.cpp:118
rtabmap_conversions::transformToPoseMsg
void transformToPoseMsg(const rtabmap::Transform &transform, geometry_msgs::Pose &msg)
Definition: MsgConversion.cpp:106
rtabmap_conversions::nodeInfoFromROS
rtabmap::Signature nodeInfoFromROS(const rtabmap_msgs::Node &msg)
Definition: MsgConversion.cpp:1544
Statistics.h
rtabmap::Transform::getIdentity
static Transform getIdentity()
rtabmap::CameraModel
rtabmap_conversions::mapGraphFromROS
void mapGraphFromROS(const rtabmap_msgs::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
Definition: MsgConversion.cpp:1014
rtabmap_conversions::cameraModelToROS
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Definition: MsgConversion.cpp:869
rtabmap_conversions::points3fToROS
void points3fToROS(const std::vector< cv::Point3f > &pts, std::vector< rtabmap_msgs::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform())
Definition: MsgConversion.cpp:777
rtabmap_conversions::cameraModelFromROS
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
Definition: MsgConversion.cpp:795
copy
int EIGEN_BLAS_FUNC() copy(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
rtabmap_conversions::globalDescriptorToROS
void globalDescriptorToROS(const rtabmap::GlobalDescriptor &desc, rtabmap_msgs::GlobalDescriptor &msg)
Definition: MsgConversion.cpp:631
rtabmap_conversions::userDataToROS
void userDataToROS(const cv::Mat &data, rtabmap_msgs::UserData &dataMsg, bool compress)
Definition: MsgConversion.cpp:1844
rtabmap_conversions::odomInfoToStatistics
std::map< std::string, float > odomInfoToStatistics(const rtabmap::OdometryInfo &info)
Definition: MsgConversion.cpp:1568
rtabmap_conversions::linkToROS
void linkToROS(const rtabmap::Link &link, rtabmap_msgs::Link &msg)
Definition: MsgConversion.cpp:568
rtabmap::LaserScan
rtabmap_conversions::convertRGBDMsgs
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::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &rgb, cv::Mat &depth, std::vector< rtabmap::CameraModel > &cameraModels, std::vector< rtabmap::StereoCameraModel > &stereoCameraModels, tf::TransformListener &listener, double waitForTransform, bool alreadRectifiedImages, const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPointsMsgs=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3dMsgs=std::vector< std::vector< rtabmap_msgs::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)
Definition: MsgConversion.cpp:2042
rtabmap::Landmarks
std::map< int, Landmark > Landmarks
desc
desc
rtabmap_conversions::userDataFromROS
cv::Mat userDataFromROS(const rtabmap_msgs::UserData &dataMsg)
Definition: MsgConversion.cpp:1820
rtabmap_conversions::envSensorFromROS
rtabmap::EnvSensor envSensorFromROS(const rtabmap_msgs::EnvSensor &msg)
Definition: MsgConversion.cpp:665
rtabmap_conversions::odomInfoFromROS
rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_msgs::OdomInfo &msg, bool ignoreData=false)
Definition: MsgConversion.cpp:1659
rtabmap_conversions::point3fFromROS
cv::Point3f point3fFromROS(const rtabmap_msgs::Point3f &msg)
Definition: MsgConversion.cpp:735
rtabmap_conversions::landmarksFromROS
rtabmap::Landmarks landmarksFromROS(const std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > &tags, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, tf::TransformListener &listener, double waitForTransform, double defaultLinVariance, double defaultAngVariance)
Definition: MsgConversion.cpp:1903
rtabmap_conversions::odomInfoToROS
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_msgs::OdomInfo &msg, bool ignoreData=false)
Definition: MsgConversion.cpp:1738
rtabmap::IMU
compress
def compress(data)
rtabmap_conversions::compressedMatToBytes
void compressedMatToBytes(const cv::Mat &compressed, std::vector< unsigned char > &bytes)
Definition: MsgConversion.cpp:433
rtabmap_conversions::nodeToROS
void nodeToROS(const rtabmap::Signature &signature, rtabmap_msgs::Node &msg)
Definition: MsgConversion.cpp:1463
rtabmap_conversions::stereoCameraModelFromROS
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())
Definition: MsgConversion.cpp:934
data
int data[]
stats
bool stats
rtabmap_conversions::keypointsToROS
void keypointsToROS(const std::vector< cv::KeyPoint > &kpts, std::vector< rtabmap_msgs::KeyPoint > &msg)
Definition: MsgConversion.cpp:617
rtabmap_conversions::nodeDataFromROS
rtabmap::Signature nodeDataFromROS(const rtabmap_msgs::Node &msg)
Definition: MsgConversion.cpp:1535
frameId
std::string const * frameId(const M &m)
rtabmap_conversions::point2fToROS
void point2fToROS(const cv::Point2f &kpt, rtabmap_msgs::Point2f &msg)
Definition: MsgConversion.cpp:710
rtabmap_conversions::infoFromROS
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
Definition: MsgConversion.cpp:458
rtabmap_conversions::point2fFromROS
cv::Point2f point2fFromROS(const rtabmap_msgs::Point2f &msg)
Definition: MsgConversion.cpp:705
rtabmap_conversions::keypointToROS
void keypointToROS(const cv::KeyPoint &kpt, rtabmap_msgs::KeyPoint &msg)
Definition: MsgConversion.cpp:585
info
else if n * info
rtabmap_conversions::sensorDataToROS
void sensorDataToROS(const rtabmap::SensorData &signature, rtabmap_msgs::SensorData &msg, const std::string &frameId="base_link", bool copyRawData=false)
Definition: MsgConversion.cpp:1252
rtabmap_conversions::envSensorsFromROS
rtabmap::EnvSensors envSensorsFromROS(const std::vector< rtabmap_msgs::EnvSensor > &msg)
Definition: MsgConversion.cpp:677
rtabmap_conversions::toCvCopy
void toCvCopy(const rtabmap_msgs::RGBDImage &image, cv_bridge::CvImagePtr &rgb, cv_bridge::CvImagePtr &depth)
Definition: MsgConversion.cpp:136
rtabmap::GlobalDescriptor
tf::Transform
slerp
GLM_FUNC_DECL detail::tquat< T, P > slerp(detail::tquat< T, P > const &x, detail::tquat< T, P > const &y, T const &a)
model
noiseModel::Diagonal::shared_ptr model
rtabmap_conversions::nodeInfoToROS
void nodeInfoToROS(const rtabmap::Signature &signature, rtabmap_msgs::Node &msg)
Definition: MsgConversion.cpp:1556
rtabmap_conversions::infoToROS
void infoToROS(const rtabmap::Statistics &stats, rtabmap_msgs::Info &info)
Definition: MsgConversion.cpp:526
TimeBase< Time, Duration >::sec
uint32_t sec
rtabmap_conversions::nodeDataToROS
void nodeDataToROS(const rtabmap::Signature &signature, rtabmap_msgs::Node &msg)
Definition: MsgConversion.cpp:1539
StereoCameraModel.h
TimeBase< Time, Duration >::nsec
uint32_t nsec
rtabmap_conversions::compressedMatFromBytes
cv::Mat compressedMatFromBytes(const std::vector< unsigned char > &bytes, bool copy=true)
Definition: MsgConversion.cpp:444
rtabmap_conversions::keypointFromROS
cv::KeyPoint keypointFromROS(const rtabmap_msgs::KeyPoint &msg)
Definition: MsgConversion.cpp:580
transform_listener.h
tf.h
rtabmap::Transform
OdometryInfo.h
rtabmap_conversions::timestampFromROS
double timestampFromROS(const ros::Time &stamp)
Definition: MsgConversion.h:198
rtabmap::EnvSensors
std::map< EnvSensor::Type, EnvSensor > EnvSensors
rtabmap_conversions::getMovingTransform
rtabmap::Transform getMovingTransform(const std::string &movingFrame, const std::string &fixedFrame, const ros::Time &stampFrom, const ros::Time &stampTo, tf::TransformListener &listener, double waitForTransform)
Definition: MsgConversion.cpp:2007
ros::Time
rtabmap_conversions::transformFromTF
rtabmap::Transform transformFromTF(const tf::Transform &transform)
Definition: MsgConversion.cpp:64
rtabmap_conversions::imuFromROS
rtabmap::IMU imuFromROS(const sensor_msgs::Imu &msg, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
Definition: MsgConversion.cpp:1866
rtabmap_conversions
Definition: MsgConversion.h:64
cv_bridge.h
rtabmap_conversions::points3fFromROS
std::vector< cv::Point3f > points3fFromROS(const std::vector< rtabmap_msgs::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform())
Definition: MsgConversion.cpp:747
rtabmap_conversions::transformToGeometryMsg
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
Definition: MsgConversion.cpp:71
rtabmap_conversions::mapDataToROS
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_msgs::MapData &msg)
Definition: MsgConversion.cpp:993
tf::TransformListener
rtabmap::OdometryInfo
rtabmap_conversions::imuToROS
void imuToROS(const rtabmap::IMU &imu, sensor_msgs::Imu &msg)
Definition: MsgConversion.cpp:1877
rtabmap_conversions::points2fFromROS
std::vector< cv::Point2f > points2fFromROS(const std::vector< rtabmap_msgs::Point2f > &msg)
Definition: MsgConversion.cpp:716
rtabmap_conversions::envSensorsToROS
void envSensorsToROS(const rtabmap::EnvSensors &sensors, std::vector< rtabmap_msgs::EnvSensor > &msg)
Definition: MsgConversion.cpp:691
Signature.h
rtabmap_conversions::rgbdImageFromROS
rtabmap::SensorData rgbdImageFromROS(const rtabmap_msgs::RGBDImageConstPtr &image)
Definition: MsgConversion.cpp:288
rtabmap_conversions::convertScan3dMsg
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, bool is2D=false)
Definition: MsgConversion.cpp:2751
transform
EIGEN_DONT_INLINE void transform(const Quaternion< Scalar > &t, Data &data)
rtabmap_conversions::mapDataFromROS
void mapDataFromROS(const rtabmap_msgs::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
Definition: MsgConversion.cpp:977
rtabmap_conversions::envSensorToROS
void envSensorToROS(const rtabmap::EnvSensor &sensor, rtabmap_msgs::EnvSensor &msg)
Definition: MsgConversion.cpp:670
rtabmap_conversions::convertStereoMsg
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)
Definition: MsgConversion.cpp:2435
rtabmap_conversions::rgbdImageToROS
void rgbdImageToROS(const rtabmap::SensorData &data, rtabmap_msgs::RGBDImage &msg, const std::string &sensorFrameId)
Definition: MsgConversion.cpp:212
rtabmap::EnvSensor
rtabmap_conversions::linkFromROS
rtabmap::Link linkFromROS(const rtabmap_msgs::Link &msg)
Definition: MsgConversion.cpp:562
Transform.h
rtabmap_conversions::sensorDataFromROS
rtabmap::SensorData sensorDataFromROS(const rtabmap_msgs::SensorData &msg)
Definition: MsgConversion.cpp:1064
rtabmap::Signature
msg
msg
rtabmap_conversions::keypointsFromROS
std::vector< cv::KeyPoint > keypointsFromROS(const std::vector< rtabmap_msgs::KeyPoint > &msg)
Definition: MsgConversion.cpp:596


rtabmap_conversions
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:35:04