Go to the documentation of this file.
28 #ifndef MSGCONVERSION_H_
29 #define MSGCONVERSION_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>
41 #include <opencv2/opencv.hpp>
42 #include <opencv2/features2d/features2d.hpp>
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>
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);
110 void point2fToROS(
const cv::Point2f & kpt, rtabmap_msgs::Point2f &
msg);
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);
116 void point3fToROS(
const cv::Point3f & pt, rtabmap_msgs::Point3f &
msg);
123 const sensor_msgs::CameraInfo & camInfo,
127 sensor_msgs::CameraInfo & camInfo);
130 const sensor_msgs::CameraInfo & leftCamInfo,
131 const sensor_msgs::CameraInfo & rightCamInfo,
135 const sensor_msgs::CameraInfo & leftCamInfo,
136 const sensor_msgs::CameraInfo & rightCamInfo,
139 double waitForTransform);
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,
148 const std::map<int, rtabmap::Transform> & poses,
149 const std::multimap<int, rtabmap::Link> & links,
150 const std::map<int, rtabmap::Signature> & signatures,
152 rtabmap_msgs::MapData &
msg);
155 const rtabmap_msgs::MapGraph &
msg,
156 std::map<int, rtabmap::Transform> & poses,
157 std::multimap<int, rtabmap::Link> & links,
160 const std::map<int, rtabmap::Transform> & poses,
161 const std::multimap<int, rtabmap::Link> & links,
163 rtabmap_msgs::MapGraph &
msg);
189 const std::map<
int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> > & tags,
191 const std::string & odomFrameId,
194 double waitForTransform,
195 double defaultLinVariance,
196 double defaultAngVariance);
202 const std::string & fromFrameId,
203 const std::string & toFrameId,
206 double waitForTransform);
212 const std::string & movingFrame,
213 const std::string & fixedFrame,
217 double waitForTransform);
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,
229 std::vector<rtabmap::CameraModel> & cameraModels,
230 std::vector<rtabmap::StereoCameraModel> & stereoCameraModels,
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);
244 const sensor_msgs::CameraInfo& leftCamInfoMsg,
245 const sensor_msgs::CameraInfo& rightCamInfoMsg,
246 const std::string & frameId,
247 const std::string & odomFrameId,
253 double waitForTransform,
254 bool alreadyRectified);
257 const sensor_msgs::LaserScan & scan2dMsg,
258 const std::string & frameId,
259 const std::string & odomFrameId,
263 double waitForTransform,
264 bool outputInFrameId =
false);
267 const sensor_msgs::PointCloud2 & scan3dMsg,
268 const std::string & frameId,
269 const std::string & odomFrameId,
273 double waitForTransform,
275 float maxRange = 0.0f,
279 const sensor_msgs::PointCloud2 & input,
280 sensor_msgs::PointCloud2 & output,
281 const std::string & fixedFrameId,
283 double waitForTransform,
287 const sensor_msgs::PointCloud2 & input,
288 sensor_msgs::PointCloud2 & output,
289 double previousStamp,
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)
void transformToTF(const rtabmap::Transform &transform, tf::Transform &tfTransform)
rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform &msg)
rtabmap::Signature nodeFromROS(const rtabmap_msgs::Node &msg)
void point3fToROS(const cv::Point3f &pt, rtabmap_msgs::Point3f &msg)
void globalDescriptorsToROS(const std::vector< rtabmap::GlobalDescriptor > &desc, std::vector< rtabmap_msgs::GlobalDescriptor > &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 toCvShare(const rtabmap_msgs::RGBDImageConstPtr &image, cv_bridge::CvImageConstPtr &rgb, cv_bridge::CvImageConstPtr &depth)
void mapGraphToROS(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const rtabmap::Transform &mapToOdom, rtabmap_msgs::MapGraph &msg)
std::vector< rtabmap::GlobalDescriptor > globalDescriptorsFromROS(const std::vector< rtabmap_msgs::GlobalDescriptor > &msg)
rtabmap::GlobalDescriptor globalDescriptorFromROS(const rtabmap_msgs::GlobalDescriptor &msg)
void points2fToROS(const std::vector< cv::Point2f > &kpts, std::vector< rtabmap_msgs::Point2f > &msg)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
void transformToPoseMsg(const rtabmap::Transform &transform, geometry_msgs::Pose &msg)
rtabmap::Signature nodeInfoFromROS(const rtabmap_msgs::Node &msg)
void mapGraphFromROS(const rtabmap_msgs::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
void points3fToROS(const std::vector< cv::Point3f > &pts, std::vector< rtabmap_msgs::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform())
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
int EIGEN_BLAS_FUNC() copy(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
void globalDescriptorToROS(const rtabmap::GlobalDescriptor &desc, rtabmap_msgs::GlobalDescriptor &msg)
void userDataToROS(const cv::Mat &data, rtabmap_msgs::UserData &dataMsg, bool compress)
std::map< std::string, float > odomInfoToStatistics(const rtabmap::OdometryInfo &info)
void linkToROS(const rtabmap::Link &link, rtabmap_msgs::Link &msg)
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)
std::map< int, Landmark > Landmarks
cv::Mat userDataFromROS(const rtabmap_msgs::UserData &dataMsg)
rtabmap::EnvSensor envSensorFromROS(const rtabmap_msgs::EnvSensor &msg)
rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_msgs::OdomInfo &msg, bool ignoreData=false)
cv::Point3f point3fFromROS(const rtabmap_msgs::Point3f &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)
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_msgs::OdomInfo &msg, bool ignoreData=false)
void compressedMatToBytes(const cv::Mat &compressed, std::vector< unsigned char > &bytes)
void nodeToROS(const rtabmap::Signature &signature, rtabmap_msgs::Node &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 keypointsToROS(const std::vector< cv::KeyPoint > &kpts, std::vector< rtabmap_msgs::KeyPoint > &msg)
rtabmap::Signature nodeDataFromROS(const rtabmap_msgs::Node &msg)
std::string const * frameId(const M &m)
void point2fToROS(const cv::Point2f &kpt, rtabmap_msgs::Point2f &msg)
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
cv::Point2f point2fFromROS(const rtabmap_msgs::Point2f &msg)
void keypointToROS(const cv::KeyPoint &kpt, rtabmap_msgs::KeyPoint &msg)
void sensorDataToROS(const rtabmap::SensorData &signature, rtabmap_msgs::SensorData &msg, const std::string &frameId="base_link", bool copyRawData=false)
rtabmap::EnvSensors envSensorsFromROS(const std::vector< rtabmap_msgs::EnvSensor > &msg)
void toCvCopy(const rtabmap_msgs::RGBDImage &image, cv_bridge::CvImagePtr &rgb, cv_bridge::CvImagePtr &depth)
GLM_FUNC_DECL detail::tquat< T, P > slerp(detail::tquat< T, P > const &x, detail::tquat< T, P > const &y, T const &a)
noiseModel::Diagonal::shared_ptr model
void nodeInfoToROS(const rtabmap::Signature &signature, rtabmap_msgs::Node &msg)
void infoToROS(const rtabmap::Statistics &stats, rtabmap_msgs::Info &info)
void nodeDataToROS(const rtabmap::Signature &signature, rtabmap_msgs::Node &msg)
cv::Mat compressedMatFromBytes(const std::vector< unsigned char > &bytes, bool copy=true)
cv::KeyPoint keypointFromROS(const rtabmap_msgs::KeyPoint &msg)
double timestampFromROS(const ros::Time &stamp)
std::map< EnvSensor::Type, EnvSensor > EnvSensors
rtabmap::Transform getMovingTransform(const std::string &movingFrame, const std::string &fixedFrame, const ros::Time &stampFrom, const ros::Time &stampTo, tf::TransformListener &listener, double waitForTransform)
rtabmap::Transform transformFromTF(const tf::Transform &transform)
rtabmap::IMU imuFromROS(const sensor_msgs::Imu &msg, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
std::vector< cv::Point3f > points3fFromROS(const std::vector< rtabmap_msgs::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform())
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &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_msgs::MapData &msg)
void imuToROS(const rtabmap::IMU &imu, sensor_msgs::Imu &msg)
std::vector< cv::Point2f > points2fFromROS(const std::vector< rtabmap_msgs::Point2f > &msg)
void envSensorsToROS(const rtabmap::EnvSensors &sensors, std::vector< rtabmap_msgs::EnvSensor > &msg)
rtabmap::SensorData rgbdImageFromROS(const rtabmap_msgs::RGBDImageConstPtr &image)
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)
EIGEN_DONT_INLINE void transform(const Quaternion< Scalar > &t, Data &data)
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)
void envSensorToROS(const rtabmap::EnvSensor &sensor, rtabmap_msgs::EnvSensor &msg)
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 rgbdImageToROS(const rtabmap::SensorData &data, rtabmap_msgs::RGBDImage &msg, const std::string &sensorFrameId)
rtabmap::Link linkFromROS(const rtabmap_msgs::Link &msg)
rtabmap::SensorData sensorDataFromROS(const rtabmap_msgs::SensorData &msg)
std::vector< cv::KeyPoint > keypointsFromROS(const std::vector< rtabmap_msgs::KeyPoint > &msg)