28 #ifndef MSGCONVERSION_H_ 29 #define MSGCONVERSION_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> 39 #include <opencv2/opencv.hpp> 40 #include <opencv2/features2d/features2d.hpp> 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> 88 void keypointToROS(
const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
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);
94 void point2fToROS(
const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
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);
100 void point3fToROS(
const cv::Point3f & kpt, rtabmap_ros::Point3f & msg);
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);
106 const sensor_msgs::CameraInfo & camInfo,
110 sensor_msgs::CameraInfo & camInfo);
113 const sensor_msgs::CameraInfo & leftCamInfo,
114 const sensor_msgs::CameraInfo & rightCamInfo,
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,
124 const std::map<int, rtabmap::Transform> & poses,
125 const std::multimap<int, rtabmap::Link> & links,
126 const std::map<int, rtabmap::Signature> & signatures,
128 rtabmap_ros::MapData & msg);
131 const rtabmap_ros::MapGraph & msg,
132 std::map<int, rtabmap::Transform> & poses,
133 std::multimap<int, rtabmap::Link> & links,
136 const std::map<int, rtabmap::Transform> & poses,
137 const std::multimap<int, rtabmap::Link> & links,
139 rtabmap_ros::MapGraph & msg);
151 void userDataToROS(
const cv::Mat & data, rtabmap_ros::UserData & dataMsg,
bool compress);
157 const std::string & fromFrameId,
158 const std::string & toFrameId,
161 double waitForTransform);
167 const std::string & sourceTargetFrame,
168 const std::string & fixedFrame,
172 double waitForTransform);
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,
183 std::vector<rtabmap::CameraModel> & cameraModels,
185 double waitForTransform);
190 const sensor_msgs::CameraInfo& leftCamInfoMsg,
191 const sensor_msgs::CameraInfo& rightCamInfoMsg,
192 const std::string & frameId,
193 const std::string & odomFrameId,
199 double waitForTransform);
202 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
203 const std::string & frameId,
204 const std::string & odomFrameId,
209 double waitForTransform);
212 const sensor_msgs::PointCloud2ConstPtr & scan3dMsg,
213 const std::string & frameId,
214 const std::string & odomFrameId,
219 double waitForTransform);
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)
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)