$search
00001 // $Id: ButOctomapROS.h 1669 2011-06-27 15:58:35Z hornunga@informatik.uni-freiburg.de $ 00002 00011 /* 00012 * Copyright (c) 2010, A. Hornung, University of Freiburg 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions are met: 00017 * 00018 * * Redistributions of source code must retain the above copyright 00019 * notice, this list of conditions and the following disclaimer. 00020 * * Redistributions in binary form must reproduce the above copyright 00021 * notice, this list of conditions and the following disclaimer in the 00022 * documentation and/or other materials provided with the distribution. 00023 * * Neither the name of the University of Freiburg nor the names of its 00024 * contributors may be used to endorse or promote products derived from 00025 * this software without specific prior written permission. 00026 * 00027 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00028 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00029 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00030 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00031 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00032 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00033 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00034 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00035 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00036 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 * POSSIBILITY OF SUCH DAMAGE. 00038 */ 00039 00047 #pragma once 00048 #ifndef BUTOCTOMAP_ROS_H_ 00049 #define BUTOCTOMAP_ROS_H_ 00050 00051 00052 #include <sensor_msgs/PointCloud2.h> 00053 #include <pcl/point_cloud.h> 00054 #include <pcl/point_types.h> 00055 #include <pcl/ros/conversions.h> 00056 #include <tf/transform_datatypes.h> 00057 00058 #include <geometry_msgs/Point.h> 00059 #include <geometry_msgs/Vector3.h> 00060 #include <octomap/octomap.h> 00061 #include <octomap_ros/conversions.h> 00062 00063 namespace octomap { 00064 00065 00074 template <class OctreeT> 00075 class ButOctomapROS { 00076 public: 00077 ButOctomapROS(double resolution); 00078 ButOctomapROS(OctreeT * tree); 00079 virtual ~ButOctomapROS() {} 00080 00091 template <class PointT> 00092 void insertScan(const sensor_msgs::PointCloud2& scan, const PointT& origin, 00093 double maxrange=-1., bool pruning=true, bool dirty=false); 00094 00104 template <class PCLPointT, class PointT> 00105 void insertScan(const pcl::PointCloud<PCLPointT>& scan, const PointT& origin, 00106 double maxrange=-1., bool pruning=true, bool dirty=false); 00107 00119 template <class PCLPointT, class PCLQuaternionT> 00120 void insertScan(const pcl::PointCloud<PCLPointT>& scan, const PCLPointT& sensor_origin, 00121 const PCLPointT& frame_origin_trans, const PCLQuaternionT& frame_origin_rot, 00122 double maxrange=-1., bool pruning=true, bool dirty=false); 00123 00124 00125 00126 00141 template <class PointT> 00142 bool castRay(const PointT& origin, const PointT& direction, PointT& end, 00143 bool ignoreUnknownCells = false, double maxRange = -1.0) const; 00144 00155 template <class PointT> 00156 bool insertRay(const PointT& origin, const PointT& end, double maxRange = -1.0); 00157 00158 00166 template <class PointT> 00167 typename OctreeT::NodeType* search(const PointT& point) const; 00168 00169 typename OctreeT::NodeType* search(const tf::Point& point) const; 00170 typedef OctreeT OcTreeType; 00171 typedef typename OctreeT::NodeType NodeType; 00172 typedef boost::shared_ptr<OctreeT> OctreePtr; 00173 00174 OctreeT & getTree() { return *octree; } 00175 00176 void setTree(OctreeT * tree); 00177 00178 protected: 00179 OctreePtr octree; 00180 }; 00181 00188 typedef ButOctomapROS<OcTree> OcTreeROS; 00189 00190 00191 00192 // 00193 // Implementation: 00194 // 00195 00196 template <class OctreeT> 00197 ButOctomapROS<OctreeT>::ButOctomapROS(double resolution) 00198 : octree( new OctreeT(resolution) ) 00199 { 00200 00201 } 00202 00203 template <class OctreeT> 00204 ButOctomapROS<OctreeT>::ButOctomapROS(OctreeT * tree) 00205 : octree( tree ) 00206 { 00207 00208 } 00209 00210 template <class OctreeT> 00211 void ButOctomapROS<OctreeT>::setTree(OctreeT * tree) 00212 { 00213 if( tree != 0 ) 00214 { 00215 octree->clear(); 00216 octree = OctreePtr( tree ); 00217 } 00218 00219 } 00220 00221 template <class OctreeT> 00222 template <class PCLPointT, class PointT> 00223 void ButOctomapROS<OctreeT>::insertScan(const pcl::PointCloud<PCLPointT>& scan, const PointT& origin, 00224 double maxrange, bool pruning, bool dirty){ 00225 00226 Pointcloud pc; 00227 pointcloudPCLToOctomap(scan, pc); 00228 00229 octree->insertScan(pc, point3d(origin.x, origin.y, origin.z), maxrange, pruning, dirty); 00230 00231 } 00232 00233 00234 template <class OctreeT> 00235 template <class PCLPointT, class PCLQuaternionT> 00236 void ButOctomapROS<OctreeT>::insertScan(const pcl::PointCloud<PCLPointT>& scan, const PCLPointT& sensor_origin, 00237 const PCLPointT& frame_origin_trans, const PCLQuaternionT& frame_origin_rot, double maxrange, bool pruning, bool dirty) 00238 { 00239 00240 Pointcloud pc; 00241 pointcloudPCLToOctomap(scan, pc); 00242 00243 pose6d frame_origin; 00244 frame_origin.trans() = point3d(frame_origin_trans.x, frame_origin_trans.y, frame_origin_trans.z); 00245 frame_origin.rot() = octomath::Quaternion(frame_origin_rot.w(), 00246 frame_origin_rot.x(), frame_origin_rot.y(), frame_origin_rot.z()); 00247 octree->insertScan(pc, point3d(sensor_origin.x, sensor_origin.y, sensor_origin.z), frame_origin, 00248 maxrange, pruning, dirty); 00249 00250 } 00251 00252 00253 template <class OctreeT> 00254 template <class PointT> 00255 void ButOctomapROS<OctreeT>::insertScan(const sensor_msgs::PointCloud2& scan, const PointT& origin, 00256 double maxrange, bool pruning, bool dirty){ 00257 00258 00259 pcl::PointCloud<pcl::PointXYZ> pc; 00260 pcl::fromROSMsg(scan, pc); 00261 insertScan(pc, origin, maxrange, pruning, dirty); 00262 00263 } 00264 00265 template <class OctreeT> 00266 template <class PointT> 00267 bool ButOctomapROS<OctreeT>::insertRay(const PointT& origin, const PointT& end, double maxRange){ 00268 00269 return octree->insertRay(point3d(origin.x, origin.y, origin.z), 00270 point3d(end.x, end.y, end.z),maxRange); 00271 00272 } 00273 00274 template <class OctreeT> 00275 template <class PointT> 00276 bool ButOctomapROS<OctreeT>::castRay(const PointT& origin, const PointT& direction, 00277 PointT& end, bool ignoreUnknownCells, double maxRange) const{ 00278 00279 point3d ptEnd; 00280 bool result = octree->castRay(point3d(origin.x, origin.y, origin.z), point3d(direction.x, direction.y, direction.z), 00281 ptEnd, ignoreUnknownCells, maxRange); 00282 00283 end.x = ptEnd.x(); 00284 end.y = ptEnd.y(); 00285 end.z = ptEnd.z(); 00286 00287 return result; 00288 } 00289 00290 00291 template <class OctreeT> 00292 template <class PointT> 00293 typename OctreeT::NodeType* ButOctomapROS<OctreeT>::search(const PointT& point) const{ 00294 return octree->search(point.x, point.y, point.z); 00295 } 00296 00297 template <class OctreeT> 00298 typename OctreeT::NodeType* ButOctomapROS<OctreeT>::search(const tf::Point& point) const{ 00299 return octree->search(point.x(), point.y(), point.z()); 00300 } 00301 00302 } 00303 00304 #endif /* BUTButOctomapROS_H_ */ 00305