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 <geometry_msgs/Transform.h>
00033 #include <geometry_msgs/Pose.h>
00034 #include <sensor_msgs/CameraInfo.h>
00035 
00036 #include <opencv2/opencv.hpp>
00037 #include <opencv2/features2d/features2d.hpp>
00038 
00039 #include <rtabmap/core/Transform.h>
00040 #include <rtabmap/core/Link.h>
00041 #include <rtabmap/core/Signature.h>
00042 #include <rtabmap/core/OdometryInfo.h>
00043 #include <rtabmap/core/Statistics.h>
00044 #include <rtabmap/core/StereoCameraModel.h>
00045 
00046 #include <rtabmap_ros/Link.h>
00047 #include <rtabmap_ros/KeyPoint.h>
00048 #include <rtabmap_ros/Point2f.h>
00049 #include <rtabmap_ros/Point3f.h>
00050 #include <rtabmap_ros/MapData.h>
00051 #include <rtabmap_ros/MapGraph.h>
00052 #include <rtabmap_ros/NodeData.h>
00053 #include <rtabmap_ros/OdomInfo.h>
00054 #include <rtabmap_ros/Info.h>
00055 
00056 namespace rtabmap_ros {
00057 
00058 void transformToTF(const rtabmap::Transform & transform, tf::Transform & tfTransform);
00059 rtabmap::Transform transformFromTF(const tf::Transform & transform);
00060 
00061 void transformToGeometryMsg(const rtabmap::Transform & transform, geometry_msgs::Transform & msg);
00062 rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform & msg);
00063 
00064 void transformToPoseMsg(const rtabmap::Transform & transform, geometry_msgs::Pose & msg);
00065 rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose & msg);
00066 
00067 // copy data
00068 void compressedMatToBytes(const cv::Mat & compressed, std::vector<unsigned char> & bytes);
00069 cv::Mat compressedMatFromBytes(const std::vector<unsigned char> & bytes, bool copy = true);
00070 
00071 void infoFromROS(const rtabmap_ros::Info & info, rtabmap::Statistics & stat);
00072 void infoToROS(const rtabmap::Statistics & stats, rtabmap_ros::Info & info);
00073 
00074 rtabmap::Link linkFromROS(const rtabmap_ros::Link & msg);
00075 void linkToROS(const rtabmap::Link & link, rtabmap_ros::Link & msg);
00076 
00077 cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint & msg);
00078 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
00079 
00080 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg);
00081 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_ros::KeyPoint> & msg);
00082 
00083 cv::Point2f point2fFromROS(const rtabmap_ros::Point2f & msg);
00084 void point2fToROS(const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
00085 
00086 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_ros::Point2f> & msg);
00087 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_ros::Point2f> & msg);
00088 
00089 cv::Point3f point3fFromROS(const rtabmap_ros::Point3f & msg);
00090 void point3fToROS(const cv::Point3f & kpt, rtabmap_ros::Point3f & msg);
00091 
00092 std::vector<cv::Point3f> points3fFromROS(const std::vector<rtabmap_ros::Point3f> & msg);
00093 void points3fToROS(const std::vector<cv::Point3f> & kpts, std::vector<rtabmap_ros::Point3f> & msg);
00094 
00095 rtabmap::CameraModel cameraModelFromROS(
00096                 const sensor_msgs::CameraInfo & camInfo,
00097                 const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
00098 void cameraModelToROS(
00099                 const rtabmap::CameraModel & model,
00100                 sensor_msgs::CameraInfo & camInfo);
00101 
00102 rtabmap::StereoCameraModel stereoCameraModelFromROS(
00103                 const sensor_msgs::CameraInfo & leftCamInfo,
00104                 const sensor_msgs::CameraInfo & rightCamInfo,
00105                 const rtabmap::Transform & localTransform = rtabmap::Transform::getIdentity());
00106 
00107 void mapDataFromROS(
00108                 const rtabmap_ros::MapData & msg,
00109                 std::map<int, rtabmap::Transform> & poses,
00110                 std::multimap<int, rtabmap::Link> & links,
00111                 std::map<int, rtabmap::Signature> & signatures,
00112                 rtabmap::Transform & mapToOdom);
00113 void mapDataToROS(
00114                 const std::map<int, rtabmap::Transform> & poses,
00115                 const std::multimap<int, rtabmap::Link> & links,
00116                 const std::map<int, rtabmap::Signature> & signatures,
00117                 const rtabmap::Transform & mapToOdom,
00118                 rtabmap_ros::MapData & msg);
00119 
00120 void mapGraphFromROS(
00121                 const rtabmap_ros::MapGraph & msg,
00122                 std::map<int, rtabmap::Transform> & poses,
00123                 std::multimap<int, rtabmap::Link> & links,
00124                 rtabmap::Transform & mapToOdom);
00125 void mapGraphToROS(
00126                 const std::map<int, rtabmap::Transform> & poses,
00127                 const std::multimap<int, rtabmap::Link> & links,
00128                 const rtabmap::Transform & mapToOdom,
00129                 rtabmap_ros::MapGraph & msg);
00130 
00131 rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg);
00132 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
00133 
00134 rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData & msg);
00135 void nodeInfoToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
00136 
00137 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo & msg);
00138 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_ros::OdomInfo & msg);
00139 
00140 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
00141 
00142 }
00143 
00144 #endif /* MSGCONVERSION_H_ */


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Sun Jul 24 2016 03:49:08