MsgConversion.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef MSGCONVERSION_H_
00029 #define MSGCONVERSION_H_
00030 
00031 #include <tf/tf.h>
00032 #include <tf/transform_listener.h>
00033 #include <geometry_msgs/Transform.h>
00034 #include <geometry_msgs/Pose.h>
00035 #include <sensor_msgs/CameraInfo.h>
00036 #include <sensor_msgs/LaserScan.h>
00037 #include <sensor_msgs/Image.h>
00038 
00039 #include <opencv2/opencv.hpp>
00040 #include <opencv2/features2d/features2d.hpp>
00041 #include <cv_bridge/cv_bridge.h>
00042 
00043 #include <rtabmap/core/Transform.h>
00044 #include <rtabmap/core/Link.h>
00045 #include <rtabmap/core/Signature.h>
00046 #include <rtabmap/core/OdometryInfo.h>
00047 #include <rtabmap/core/Statistics.h>
00048 #include <rtabmap/core/StereoCameraModel.h>
00049 
00050 #include <rtabmap_ros/Link.h>
00051 #include <rtabmap_ros/KeyPoint.h>
00052 #include <rtabmap_ros/Point2f.h>
00053 #include <rtabmap_ros/Point3f.h>
00054 #include <rtabmap_ros/MapData.h>
00055 #include <rtabmap_ros/MapGraph.h>
00056 #include <rtabmap_ros/NodeData.h>
00057 #include <rtabmap_ros/OdomInfo.h>
00058 #include <rtabmap_ros/Info.h>
00059 #include <rtabmap_ros/RGBDImage.h>
00060 #include <rtabmap_ros/UserData.h>
00061 
00062 namespace rtabmap_ros {
00063 
00064 void transformToTF(const rtabmap::Transform & transform, tf::Transform & tfTransform);
00065 rtabmap::Transform transformFromTF(const tf::Transform & transform);
00066 
00067 void transformToGeometryMsg(const rtabmap::Transform & transform, geometry_msgs::Transform & msg);
00068 rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform & msg);
00069 
00070 void transformToPoseMsg(const rtabmap::Transform & transform, geometry_msgs::Pose & msg);
00071 rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose & msg);
00072 
00073 void toCvCopy(const rtabmap_ros::RGBDImage & image, cv_bridge::CvImagePtr & rgb, cv_bridge::CvImagePtr & depth);
00074 void toCvShare(const rtabmap_ros::RGBDImageConstPtr & image, cv_bridge::CvImageConstPtr & rgb, cv_bridge::CvImageConstPtr & depth);
00075 rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::RGBDImageConstPtr & image);
00076 
00077 // copy data
00078 void compressedMatToBytes(const cv::Mat & compressed, std::vector<unsigned char> & bytes);
00079 cv::Mat compressedMatFromBytes(const std::vector<unsigned char> & bytes, bool copy = true);
00080 
00081 void infoFromROS(const rtabmap_ros::Info & info, rtabmap::Statistics & stat);
00082 void infoToROS(const rtabmap::Statistics & stats, rtabmap_ros::Info & info);
00083 
00084 rtabmap::Link linkFromROS(const rtabmap_ros::Link & msg);
00085 void linkToROS(const rtabmap::Link & link, rtabmap_ros::Link & msg);
00086 
00087 cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint & msg);
00088 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
00089 
00090 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg);
00091 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_ros::KeyPoint> & msg);
00092 
00093 cv::Point2f point2fFromROS(const rtabmap_ros::Point2f & msg);
00094 void point2fToROS(const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
00095 
00096 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_ros::Point2f> & msg);
00097 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_ros::Point2f> & msg);
00098 
00099 cv::Point3f point3fFromROS(const rtabmap_ros::Point3f & msg);
00100 void point3fToROS(const cv::Point3f & kpt, rtabmap_ros::Point3f & msg);
00101 
00102 std::vector<cv::Point3f> points3fFromROS(const std::vector<rtabmap_ros::Point3f> & msg);
00103 void points3fToROS(const std::vector<cv::Point3f> & kpts, std::vector<rtabmap_ros::Point3f> & msg);
00104 
00105 rtabmap::CameraModel cameraModelFromROS(
00106                 const sensor_msgs::CameraInfo & camInfo,
00107                 const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
00108 void cameraModelToROS(
00109                 const rtabmap::CameraModel & model,
00110                 sensor_msgs::CameraInfo & camInfo);
00111 
00112 rtabmap::StereoCameraModel stereoCameraModelFromROS(
00113                 const sensor_msgs::CameraInfo & leftCamInfo,
00114                 const sensor_msgs::CameraInfo & rightCamInfo,
00115                 const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
00116 
00117 void mapDataFromROS(
00118                 const rtabmap_ros::MapData & msg,
00119                 std::map<int, rtabmap::Transform> & poses,
00120                 std::multimap<int, rtabmap::Link> & links,
00121                 std::map<int, rtabmap::Signature> & signatures,
00122                 rtabmap::Transform & mapToOdom);
00123 void mapDataToROS(
00124                 const std::map<int, rtabmap::Transform> & poses,
00125                 const std::multimap<int, rtabmap::Link> & links,
00126                 const std::map<int, rtabmap::Signature> & signatures,
00127                 const rtabmap::Transform & mapToOdom,
00128                 rtabmap_ros::MapData & msg);
00129 
00130 void mapGraphFromROS(
00131                 const rtabmap_ros::MapGraph & msg,
00132                 std::map<int, rtabmap::Transform> & poses,
00133                 std::multimap<int, rtabmap::Link> & links,
00134                 rtabmap::Transform & mapToOdom);
00135 void mapGraphToROS(
00136                 const std::map<int, rtabmap::Transform> & poses,
00137                 const std::multimap<int, rtabmap::Link> & links,
00138                 const rtabmap::Transform & mapToOdom,
00139                 rtabmap_ros::MapGraph & msg);
00140 
00141 rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg);
00142 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
00143 
00144 rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData & msg);
00145 void nodeInfoToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
00146 
00147 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo & msg);
00148 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_ros::OdomInfo & msg);
00149 
00150 cv::Mat userDataFromROS(const rtabmap_ros::UserData & dataMsg);
00151 void userDataToROS(const cv::Mat & data, rtabmap_ros::UserData & dataMsg, bool compress);
00152 
00153 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
00154 
00155 // common stuff
00156 rtabmap::Transform getTransform(
00157                 const std::string & fromFrameId,
00158                 const std::string & toFrameId,
00159                 const ros::Time & stamp,
00160                 tf::TransformListener & listener,
00161                 double waitForTransform);
00162 
00163 
00164 // get moving transform accordingly to a fixed frame. For example get
00165 // transform of /base_link between two stamps accordingly to /odom frame.
00166 rtabmap::Transform getTransform(
00167                 const std::string & sourceTargetFrame,
00168                 const std::string & fixedFrame,
00169                 const ros::Time & stampSource,
00170                 const ros::Time & stampTarget,
00171                 tf::TransformListener & listener,
00172                 double waitForTransform);
00173 
00174 bool convertRGBDMsgs(
00175                 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
00176                 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
00177                 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
00178                 const std::string & frameId,
00179                 const std::string & odomFrameId,
00180                 const ros::Time & odomStamp,
00181                 cv::Mat & rgb,
00182                 cv::Mat & depth,
00183                 std::vector<rtabmap::CameraModel> & cameraModels,
00184                 tf::TransformListener & listener,
00185                 double waitForTransform);
00186 
00187 bool convertStereoMsg(
00188                 const cv_bridge::CvImageConstPtr& leftImageMsg,
00189                 const cv_bridge::CvImageConstPtr& rightImageMsg,
00190                 const sensor_msgs::CameraInfo& leftCamInfoMsg,
00191                 const sensor_msgs::CameraInfo& rightCamInfoMsg,
00192                 const std::string & frameId,
00193                 const std::string & odomFrameId,
00194                 const ros::Time & odomStamp,
00195                 cv::Mat & left,
00196                 cv::Mat & right,
00197                 rtabmap::StereoCameraModel & stereoModel,
00198                 tf::TransformListener & listener,
00199                 double waitForTransform);
00200 
00201 bool convertScanMsg(
00202                 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
00203                 const std::string & frameId,
00204                 const std::string & odomFrameId,
00205                 const ros::Time & odomStamp,
00206                 cv::Mat & scan,
00207                 rtabmap::Transform & scanLocalTransform,
00208                 tf::TransformListener & listener,
00209                 double waitForTransform);
00210 
00211 bool convertScan3dMsg(
00212                 const sensor_msgs::PointCloud2ConstPtr & scan3dMsg,
00213                 const std::string & frameId,
00214                 const std::string & odomFrameId,
00215                 const ros::Time & odomStamp,
00216                 cv::Mat & scan,
00217                 rtabmap::Transform & scanLocalTransform,
00218                 tf::TransformListener & listener,
00219                 double waitForTransform);
00220 
00221 }
00222 
00223 #endif /* MSGCONVERSION_H_ */


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49