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 <pcl/point_cloud.h>
00044 #include <pcl/point_types.h>
00045 #include <geometry_msgs/Point.h>
00046 #include <tf/transform_datatypes.h>
00047
00048 namespace octomap {
00056 template <class PointT>
00057 static inline void pointsOctomapToPCL(const point3d_list& points, pcl::PointCloud<PointT>& cloud){
00058
00059 cloud.points.reserve(points.size());
00060 for (point3d_list::const_iterator it = points.begin(); it != points.end(); ++it){
00061 cloud.push_back(PointT(it->x(), it->y(), it->z()));
00062 }
00063
00064 }
00065
00072 template <class PointT>
00073 static inline void pointcloudPCLToOctomap(const pcl::PointCloud<PointT>& pclCloud, Pointcloud& octomapCloud){
00074 octomapCloud.reserve(pclCloud.points.size());
00075
00076 typename
00077 pcl::PointCloud<PointT>::const_iterator it;
00078 for (it = pclCloud.begin(); it != pclCloud.end(); ++it){
00079
00080 if (!std::isnan (it->x) && !std::isnan (it->y) && !std::isnan (it->z))
00081 octomapCloud.push_back(it->x, it->y, it->z);
00082 }
00083 }
00084
00086 static inline geometry_msgs::Point pointOctomapToMsg(const point3d& octomapPt){
00087 geometry_msgs::Point pt;
00088 pt.x = octomapPt.x();
00089 pt.y = octomapPt.y();
00090 pt.z = octomapPt.z();
00091
00092 return pt;
00093 }
00094
00096 static inline octomap::point3d pointMsgToOctomap(const geometry_msgs::Point& ptMsg){
00097 return octomap::point3d(ptMsg.x, ptMsg.y, ptMsg.z);
00098 }
00099
00101 static inline tf::Point pointOctomapToTf(const point3d& octomapPt){
00102 return tf::Point(octomapPt.x(), octomapPt.y(), octomapPt.z());
00103 }
00104
00106 static inline octomap::point3d pointTfToOctomap(const tf::Point& ptTf){
00107 return point3d(ptTf.x(), ptTf.y(), ptTf.z());
00108 }
00109
00111 template <class PointT>
00112 static inline octomap::point3d pointPCLToOctomap(const PointT& p){
00113 return point3d(p.x, p.y, p.z);
00114 }
00115
00118 template <class PointT>
00119 static inline PointT pointOctomapToPCL(const point3d& octomapPt){
00120 return PointT(octomapPt.x(), octomapPt.y(), octomapPt.z());
00121 }
00122
00124 static inline tf::Quaternion quaternionOctomapToTf(const octomath::Quaternion& octomapQ){
00125 return tf::Quaternion(octomapQ.x(), octomapQ.y(), octomapQ.z(), octomapQ.u());
00126 }
00127
00129 static inline octomath::Quaternion quaternionTfToOctomap(const tf::Quaternion& qTf){
00130 return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z());
00131 }
00132
00134 static inline tf::Pose poseOctomapToTf(const octomap::pose6d& octomapPose){
00135 return tf::Pose(quaternionOctomapToTf(octomapPose.rot()), pointOctomapToTf(octomapPose.trans()));
00136 }
00137
00139 static inline octomap::pose6d poseTfToOctomap(const tf::Pose& poseTf){
00140 return octomap::pose6d(pointTfToOctomap(poseTf.getOrigin()), quaternionTfToOctomap(poseTf.getRotation()));
00141 }
00142
00143
00144
00145
00146
00147 }
00148
00149
00150 #endif
00151