MsgConversion.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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/LinearMath/Transform.h>
00032 
00033 #include <geometry_msgs/Transform.h>
00034 #include <geometry_msgs/Pose.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 
00045 #include <rtabmap_ros/Link.h>
00046 #include <rtabmap_ros/KeyPoint.h>
00047 #include <rtabmap_ros/Point2f.h>
00048 #include <rtabmap_ros/MapData.h>
00049 #include <rtabmap_ros/Graph.h>
00050 #include <rtabmap_ros/NodeData.h>
00051 #include <rtabmap_ros/OdomInfo.h>
00052 #include <rtabmap_ros/Info.h>
00053 
00054 namespace rtabmap_ros {
00055 
00056 void transformToTF(const rtabmap::Transform & transform, tf::Transform & tfTransform);
00057 rtabmap::Transform transformFromTF(const tf::Transform & transform);
00058 
00059 void transformToGeometryMsg(const rtabmap::Transform & transform, geometry_msgs::Transform & msg);
00060 rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform & msg);
00061 
00062 void transformToPoseMsg(const rtabmap::Transform & transform, geometry_msgs::Pose & msg);
00063 rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose & msg);
00064 
00065 // copy data
00066 void compressedMatToBytes(const cv::Mat & compressed, std::vector<unsigned char> & bytes);
00067 cv::Mat compressedMatFromBytes(const std::vector<unsigned char> & bytes, bool copy = true);
00068 
00069 void infoFromROS(const rtabmap_ros::Info & info, rtabmap::Statistics & stat);
00070 void infoToROS(const rtabmap::Statistics & stats, rtabmap_ros::Info & info);
00071 
00072 rtabmap::Link linkFromROS(const rtabmap_ros::Link & msg);
00073 void linkToROS(const rtabmap::Link & link, rtabmap_ros::Link & msg);
00074 
00075 cv::KeyPoint keypointFromROS(const rtabmap_ros::KeyPoint & msg);
00076 void keypointToROS(const cv::KeyPoint & kpt, rtabmap_ros::KeyPoint & msg);
00077 
00078 std::vector<cv::KeyPoint> keypointsFromROS(const std::vector<rtabmap_ros::KeyPoint> & msg);
00079 void keypointsToROS(const std::vector<cv::KeyPoint> & kpts, std::vector<rtabmap_ros::KeyPoint> & msg);
00080 
00081 cv::Point2f point2fFromROS(const rtabmap_ros::Point2f & msg);
00082 void point2fToROS(const cv::Point2f & kpt, rtabmap_ros::Point2f & msg);
00083 
00084 std::vector<cv::Point2f> points2fFromROS(const std::vector<rtabmap_ros::Point2f> & msg);
00085 void points2fToROS(const std::vector<cv::Point2f> & kpts, std::vector<rtabmap_ros::Point2f> & msg);
00086 
00087 void mapGraphFromROS(
00088                 const rtabmap_ros::Graph & msg,
00089                 std::map<int, rtabmap::Transform> & poses,
00090                 std::map<int, int> & mapIds,
00091                 std::map<int, double> & stamps,
00092                 std::map<int, std::string> & labels,
00093                 std::map<int, std::vector<unsigned char> > & userDatas,
00094                 std::multimap<int, rtabmap::Link> & links,
00095                 rtabmap::Transform & mapToOdom);
00096 void mapGraphToROS(
00097                 const std::map<int, rtabmap::Transform> & poses,
00098                 const std::map<int, int> & mapIds,
00099                 const std::map<int, double> & stamps,
00100                 const std::map<int, std::string> & labels,
00101                 const std::map<int, std::vector<unsigned char> > & userDatas,
00102                 const std::multimap<int, rtabmap::Link> & links,
00103                 const rtabmap::Transform & mapToOdom,
00104                 rtabmap_ros::Graph & msg);
00105 
00106 rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg);
00107 void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData & msg);
00108 
00109 rtabmap::OdometryInfo odomInfoFromROS(const rtabmap_ros::OdomInfo & msg);
00110 void odomInfoToROS(const rtabmap::OdometryInfo & info, rtabmap_ros::OdomInfo & msg);
00111 
00112 inline double timestampFromROS(const ros::Time & stamp) {return double(stamp.sec) + double(stamp.nsec)/1000000000.0;}
00113 
00114 }
00115 
00116 #endif /* MSGCONVERSION_H_ */


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24