00001
00002
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
00039
00040 #ifndef OCTOMAP_CONVERT_MSGS_H
00041 #define OCTOMAP_CONVERT_MSGS_H
00042
00043 #include <octomap/octomap.h>
00044 #include <octomap_ros/OctomapBinary.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_types.h>
00047 #include <geometry_msgs/Point.h>
00048 #include <tf/transform_datatypes.h>
00049
00050 namespace octomap {
00059 template <class OctomapT>
00060 static inline void octomapMapToMsg(const OctomapT& octomap, octomap_ros::OctomapBinary& mapMsg){
00061 mapMsg.header.stamp = ros::Time::now();
00062
00063 octomapMapToMsgData(octomap, mapMsg.data);
00064 }
00065
00073 template <class OctomapT>
00074 static inline void octomapMapToMsgData(const OctomapT& octomap, std::vector<int8_t>& mapData){
00075
00076
00077
00078
00079 std::stringstream datastream;
00080 octomap.writeBinaryConst(datastream);
00081 std::string datastring = datastream.str();
00082 mapData = std::vector<int8_t>(datastring.begin(), datastring.end());
00083 }
00084
00085
00092 template <class OctomapT>
00093 static inline void octomapMsgToMap(const octomap_ros::OctomapBinary& mapMsg, OctomapT& octomap){
00094 octomapMsgDataToMap(mapMsg.data, octomap);
00095 }
00096
00104 template <class OctomapT>
00105 static inline void octomapMsgDataToMap(const std::vector<int8_t>& mapData, OctomapT& octomap){
00106 std::stringstream datastream;
00107 assert(mapData.size() > 0);
00108 datastream.write((const char*) &mapData[0], mapData.size());
00109 octomap.readBinary(datastream);
00110 }
00111
00119 template <class PointT>
00120 static inline void pointsOctomapToPCL(const point3d_list& points, pcl::PointCloud<PointT>& cloud){
00121
00122 cloud.points.reserve(points.size());
00123 for (point3d_list::const_iterator it = points.begin(); it != points.end(); ++it){
00124 cloud.push_back(PointT(it->x(), it->y(), it->z()));
00125 }
00126
00127 }
00128
00135 template <class PointT>
00136 static inline void pointcloudPCLToOctomap(const pcl::PointCloud<PointT>& pclCloud, Pointcloud& octomapCloud){
00137 octomapCloud.reserve(pclCloud.points.size());
00138
00139 typename
00140 pcl::PointCloud<PointT>::const_iterator it;
00141 for (it = pclCloud.begin(); it != pclCloud.end(); ++it){
00142
00143 if (!isnan (it->x) && !isnan (it->y) && !isnan (it->z))
00144 octomapCloud.push_back(it->x, it->y, it->z);
00145 }
00146 }
00147
00149 static inline geometry_msgs::Point pointOctomapToMsg(const point3d& octomapPt){
00150 geometry_msgs::Point pt;
00151 pt.x = octomapPt.x();
00152 pt.y = octomapPt.y();
00153 pt.z = octomapPt.z();
00154
00155 return pt;
00156 }
00157
00159 static inline octomap::point3d pointMsgToOctomap(const geometry_msgs::Point& ptMsg){
00160 return octomap::point3d(ptMsg.x, ptMsg.y, ptMsg.z);
00161 }
00162
00164 static inline tf::Point pointOctomapToTf(const point3d& octomapPt){
00165 return tf::Point(octomapPt.x(), octomapPt.y(), octomapPt.z());
00166 }
00167
00169 static inline octomap::point3d pointTfToOctomap(const tf::Point& ptTf){
00170 return point3d(ptTf.x(), ptTf.y(), ptTf.z());
00171 }
00172
00174 template <class PointT>
00175 static inline octomap::point3d pointPCLToOctomap(const PointT& p){
00176 return point3d(p.x, p.y, p.z);
00177 }
00178
00181 template <class PointT>
00182 static inline PointT pointOctomapToPCL(const point3d& octomapPt){
00183 return PointT(octomapPt.x(), octomapPt.y(), octomapPt.z());
00184 }
00185
00187 static inline tf::Quaternion quaternionOctomapToTf(const octomath::Quaternion& octomapQ){
00188 return tf::Quaternion(octomapQ.x(), octomapQ.y(), octomapQ.z(), octomapQ.u());
00189 }
00190
00192 static inline octomath::Quaternion quaternionTfToOctomap(const tf::Quaternion& qTf){
00193 return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z());
00194 }
00195
00197 static inline tf::Pose poseOctomapToTf(const octomap::pose6d& octomapPose){
00198 return tf::Pose(quaternionOctomapToTf(octomapPose.rot()), pointOctomapToTf(octomapPose.trans()));
00199 }
00200
00202 static inline octomap::pose6d poseTfToOctomap(const tf::Pose& poseTf){
00203 return octomap::pose6d(pointTfToOctomap(poseTf.getOrigin()), quaternionTfToOctomap(poseTf.getRotation()));
00204 }
00205
00206
00207
00208
00209
00210 }
00211
00212
00213 #endif
00214