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_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> 92 void keypointToROS(
const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
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);
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);
110 void point2fToROS(
const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
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);
116 void point3fToROS(
const cv::Point3f &
pt, rtabmap_ros::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_ros::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_ros::MapData & msg);
155 const rtabmap_ros::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_ros::MapGraph & msg);
176 void userDataToROS(
const cv::Mat & data, rtabmap_ros::UserData & dataMsg,
bool compress);
179 const std::map<
int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> > & tags,
181 const std::string & odomFrameId,
184 double waitForTransform,
185 double defaultLinVariance,
186 double defaultAngVariance);
192 const std::string & fromFrameId,
193 const std::string & toFrameId,
196 double waitForTransform);
202 const std::string & sourceTargetFrame,
207 double waitForTransform);
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,
215 const std::string & odomFrameId,
219 std::vector<rtabmap::CameraModel> & cameraModels,
220 std::vector<rtabmap::StereoCameraModel> & stereoCameraModels,
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);
234 const sensor_msgs::CameraInfo& leftCamInfoMsg,
235 const sensor_msgs::CameraInfo& rightCamInfoMsg,
236 const std::string & frameId,
237 const std::string & odomFrameId,
243 double waitForTransform,
244 bool alreadyRectified);
247 const sensor_msgs::LaserScan & scan2dMsg,
248 const std::string & frameId,
249 const std::string & odomFrameId,
253 double waitForTransform,
254 bool outputInFrameId =
false);
257 const sensor_msgs::PointCloud2 & scan3dMsg,
258 const std::string & frameId,
259 const std::string & odomFrameId,
263 double waitForTransform,
265 float maxRange = 0.0
f,
269 const sensor_msgs::PointCloud2 & input,
270 sensor_msgs::PointCloud2 & output,
271 const std::string & fixedFrameId,
273 double waitForTransform,
277 const sensor_msgs::PointCloud2 & input,
278 sensor_msgs::PointCloud2 & output,
279 double previousStamp,
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)
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)
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)
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)