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 toCvShare(const rtabmap_ros::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_ros::RGBDImage & msg, const std::string & sensorFrameId);
79 rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::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_ros::Info & info, rtabmap::Statistics & stat);
86 void infoToROS(const rtabmap::Statistics & stats, rtabmap_ros::Info & info);
87 
88 rtabmap::Link linkFromROS(const rtabmap_ros::Link & msg);
89 void linkToROS(const rtabmap::Link & link, rtabmap_ros::Link & msg);
90 
91 cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint & msg);
92 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
93 
94 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg);
95 void keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg, std::vector<cv::KeyPoint> & kpts, int xShift=0);
96 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_ros::KeyPoint> & msg);
97 
98 rtabmap::GlobalDescriptor globalDescriptorFromROS(const rtabmap_ros::GlobalDescriptor & msg);
99 void globalDescriptorToROS(const rtabmap::GlobalDescriptor & desc, rtabmap_ros::GlobalDescriptor & msg);
100 
101 std::vector<rtabmap::GlobalDescriptor> globalDescriptorsFromROS(const std::vector<rtabmap_ros::GlobalDescriptor> & msg);
102 void globalDescriptorsToROS(const std::vector<rtabmap::GlobalDescriptor> & desc, std::vector<rtabmap_ros::GlobalDescriptor> & msg);
103 
104 rtabmap::EnvSensor envSensorFromROS(const rtabmap_ros::EnvSensor & msg);
105 void envSensorToROS(const rtabmap::EnvSensor & sensor, rtabmap_ros::EnvSensor & msg);
106 rtabmap::EnvSensors envSensorsFromROS(const std::vector<rtabmap_ros::EnvSensor> & msg);
107 void envSensorsToROS(const rtabmap::EnvSensors & sensors, std::vector<rtabmap_ros::EnvSensor> & msg);
108 
109 cv::Point2f point2fFromROS(const rtabmap_ros::Point2f & msg);
110 void point2fToROS(const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
111 
112 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_ros::Point2f> & msg);
113 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_ros::Point2f> & msg);
114 
115 cv::Point3f point3fFromROS(const rtabmap_ros::Point3f & msg);
116 void point3fToROS(const cv::Point3f & pt, rtabmap_ros::Point3f & msg);
117 
118 std::vector<cv::Point3f> points3fFromROS(const std::vector<rtabmap_ros::Point3f> & msg, const rtabmap::Transform & transform = rtabmap::Transform());
119 void points3fFromROS(const std::vector<rtabmap_ros::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_ros::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,
139  double waitForTransform);
140 
141 void mapDataFromROS(
142  const rtabmap_ros::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_ros::MapData & msg);
153 
154 void mapGraphFromROS(
155  const rtabmap_ros::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_ros::MapGraph & msg);
164 
165 rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg);
166 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
167 
168 rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData & msg);
169 void nodeInfoToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
170 
171 std::map<std::string, float> odomInfoToStatistics(const rtabmap::OdometryInfo & info);
172 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo & msg, bool ignoreData = false);
173 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_ros::OdomInfo & msg, bool ignoreData = false);
174 
175 cv::Mat userDataFromROS(const rtabmap_ros::UserData & dataMsg);
176 void userDataToROS(const cv::Mat & data, rtabmap_ros::UserData & dataMsg, bool compress);
177 
179  const std::map<int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> > & tags,
180  const std::string & frameId,
181  const std::string & odomFrameId,
182  const ros::Time & odomStamp,
184  double waitForTransform,
185  double defaultLinVariance,
186  double defaultAngVariance);
187 
188 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
189 
190 // common stuff
192  const std::string & fromFrameId,
193  const std::string & toFrameId,
194  const ros::Time & stamp,
196  double waitForTransform);
197 
198 
199 // get moving transform accordingly to a fixed frame. For example get
200 // transform of /base_link between two stamps accordingly to /odom frame.
202  const std::string & sourceTargetFrame,
203  const std::string & fixedFrame,
204  const ros::Time & stampSource,
205  const ros::Time & stampTarget,
206  tf::TransformListener & listener,
207  double waitForTransform);
208 
209 bool convertRGBDMsgs(
210  const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
211  const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
212  const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
213  const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
214  const std::string & frameId,
215  const std::string & odomFrameId,
216  const ros::Time & odomStamp,
217  cv::Mat & rgb,
218  cv::Mat & depth,
219  std::vector<rtabmap::CameraModel> & cameraModels,
220  std::vector<rtabmap::StereoCameraModel> & stereoCameraModels,
221  tf::TransformListener & listener,
222  double waitForTransform,
223  bool alreadRectifiedImages,
224  const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPointsMsgs = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
225  const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3dMsgs = std::vector<std::vector<rtabmap_ros::Point3f> >(),
226  const std::vector<cv::Mat> & localDescriptorsMsgs = std::vector<cv::Mat>(),
227  std::vector<cv::KeyPoint> * localKeyPoints = 0,
228  std::vector<cv::Point3f> * localPoints3d = 0,
229  cv::Mat * localDescriptors = 0);
230 
231 bool convertStereoMsg(
232  const cv_bridge::CvImageConstPtr& leftImageMsg,
233  const cv_bridge::CvImageConstPtr& rightImageMsg,
234  const sensor_msgs::CameraInfo& leftCamInfoMsg,
235  const sensor_msgs::CameraInfo& rightCamInfoMsg,
236  const std::string & frameId,
237  const std::string & odomFrameId,
238  const ros::Time & odomStamp,
239  cv::Mat & left,
240  cv::Mat & right,
241  rtabmap::StereoCameraModel & stereoModel,
242  tf::TransformListener & listener,
243  double waitForTransform,
244  bool alreadyRectified);
245 
246 bool convertScanMsg(
247  const sensor_msgs::LaserScan & scan2dMsg,
248  const std::string & frameId,
249  const std::string & odomFrameId,
250  const ros::Time & odomStamp,
251  rtabmap::LaserScan & scan,
252  tf::TransformListener & listener,
253  double waitForTransform,
254  bool outputInFrameId = false);
255 
256 bool convertScan3dMsg(
257  const sensor_msgs::PointCloud2 & scan3dMsg,
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  int maxPoints = 0,
265  float maxRange = 0.0f,
266  bool is2D = false);
267 
268 bool deskew(
269  const sensor_msgs::PointCloud2 & input,
270  sensor_msgs::PointCloud2 & output,
271  const std::string & fixedFrameId,
272  tf::TransformListener & listener,
273  double waitForTransform,
274  bool slerp = false);
275 
276 bool deskew(
277  const sensor_msgs::PointCloud2 & input,
278  sensor_msgs::PointCloud2 & output,
279  double previousStamp,
280  const rtabmap::Transform & velocity);
281 
282 }
283 
284 #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)
void transformToTF(const rtabmap::Transform &transform, tf::Transform &tfTransform)
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_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)
rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData &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)
std::vector< rtabmap::GlobalDescriptor > globalDescriptorsFromROS(const std::vector< rtabmap_ros::GlobalDescriptor > &msg)
static Transform getIdentity()
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_ros::OdomInfo &msg, bool ignoreData=false)
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
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)
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)
bool deskew(const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud2 &output, const std::string &fixedFrameId, tf::TransformListener &listener, double waitForTransform, bool slerp=false)
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)
rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo &msg, bool ignoreData=false)
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)
GLM_FUNC_DECL detail::tquat< T, P > slerp(detail::tquat< T, P > const &x, detail::tquat< T, P > const &y, T const &a)
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)
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)
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)
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 Tue Jan 24 2023 04:04:40