Go to the documentation of this file.00001
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef OCTOMAP_ROS_CONVERSIONS_H
00039 #define OCTOMAP_ROS_CONVERSIONS_H
00040
00041 #include <octomap/octomap.h>
00042
00043 #include <sensor_msgs/PointCloud2.h>
00044 #include <geometry_msgs/Point.h>
00045 #include <tf/transform_datatypes.h>
00046
00047 namespace octomap {
00055 void pointsOctomapToPointCloud2(const point3d_list& points, sensor_msgs::PointCloud2& cloud);
00056
00063 void pointCloud2ToOctomap(const sensor_msgs::PointCloud2& cloud, Pointcloud& octomapCloud);
00064
00066 static inline geometry_msgs::Point pointOctomapToMsg(const point3d& octomapPt){
00067 geometry_msgs::Point pt;
00068 pt.x = octomapPt.x();
00069 pt.y = octomapPt.y();
00070 pt.z = octomapPt.z();
00071
00072 return pt;
00073 }
00074
00076 static inline octomap::point3d pointMsgToOctomap(const geometry_msgs::Point& ptMsg){
00077 return octomap::point3d(ptMsg.x, ptMsg.y, ptMsg.z);
00078 }
00079
00081 static inline tf::Point pointOctomapToTf(const point3d& octomapPt){
00082 return tf::Point(octomapPt.x(), octomapPt.y(), octomapPt.z());
00083 }
00084
00086 static inline octomap::point3d pointTfToOctomap(const tf::Point& ptTf){
00087 return point3d(ptTf.x(), ptTf.y(), ptTf.z());
00088 }
00089
00091 static inline tf::Quaternion quaternionOctomapToTf(const octomath::Quaternion& octomapQ){
00092 return tf::Quaternion(octomapQ.x(), octomapQ.y(), octomapQ.z(), octomapQ.u());
00093 }
00094
00096 static inline octomath::Quaternion quaternionTfToOctomap(const tf::Quaternion& qTf){
00097 return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z());
00098 }
00099
00101 static inline tf::Pose poseOctomapToTf(const octomap::pose6d& octomapPose){
00102 return tf::Pose(quaternionOctomapToTf(octomapPose.rot()), pointOctomapToTf(octomapPose.trans()));
00103 }
00104
00106 static inline octomap::pose6d poseTfToOctomap(const tf::Pose& poseTf){
00107 return octomap::pose6d(pointTfToOctomap(poseTf.getOrigin()), quaternionTfToOctomap(poseTf.getRotation()));
00108 }
00109
00110
00111
00112
00113
00114 }
00115
00116
00117 #endif
00118