$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * Author: Eitan Marder-Eppstein 00036 *********************************************************************/ 00037 #ifndef COSTMAP_VOXEL_COSTMAP_2D_H_ 00038 #define COSTMAP_VOXEL_COSTMAP_2D_H_ 00039 00040 #include <vector> 00041 #include <queue> 00042 #include <costmap_2d/costmap_2d.h> 00043 #include <costmap_2d/observation.h> 00044 #include <costmap_2d/cell_data.h> 00045 #include <costmap_2d/cost_values.h> 00046 #include <voxel_grid/voxel_grid.h> 00047 #include <costmap_2d/VoxelGrid.h> 00048 #include <sensor_msgs/PointCloud.h> 00049 #include <boost/thread.hpp> 00050 #include <costmap_2d/Costmap2DConfig.h> 00051 00052 namespace costmap_2d { 00057 class VoxelCostmap2D : public Costmap2D { 00058 public: 00082 VoxelCostmap2D(unsigned int cells_size_x, unsigned int cells_size_y, unsigned int cells_size_z, 00083 double xy_resolution, double z_resolution, double origin_x, double origin_y, double origin_z = 0.0, double inscribed_radius = 0.0, 00084 double circumscribed_radius = 0.0, double inflation_radius = 0.0, double obstacle_range = 0.0, 00085 double raytrace_range = 0.0, double weight = 25.0, 00086 const std::vector<unsigned char>& static_data = std::vector<unsigned char>(0), unsigned char lethal_threshold = 0, 00087 unsigned int unknown_threshold = 0, unsigned int mark_threshold = 0, unsigned char unknown_cost_value = 0); 00088 00089 00090 VoxelCostmap2D(costmap_2d::Costmap2D& costmap, 00091 double z_resolution, unsigned int cells_size_z, double origin_z=0.0, 00092 unsigned int mark_threshold=0, unsigned int unknown_threshold=0); 00093 00097 ~VoxelCostmap2D(); 00098 00106 void resetMapOutsideWindow(double wx, double wy, double w_size_x, double w_size_y); 00107 00113 void updateOrigin(double new_origin_x, double new_origin_y); 00114 00123 virtual void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info = false); 00124 00129 void getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud); 00130 00131 void getVoxelGridMessage(VoxelGrid& grid); 00132 00133 static inline void mapToWorld3D(const unsigned int mx, const unsigned int my, const unsigned int mz, 00134 const double origin_x, const double origin_y, const double origin_z, 00135 const double x_resolution, const double y_resolution, const double z_resolution, 00136 double& wx, double& wy, double& wz){ 00137 //returns the center point of the cell 00138 wx = origin_x + (mx + 0.5) * x_resolution; 00139 wy = origin_y + (my + 0.5) * y_resolution; 00140 wz = origin_z + (mz + 0.5) * z_resolution; 00141 } 00142 00143 protected: 00147 virtual void resetMaps(); 00148 00154 virtual void initMaps(unsigned int size_x, unsigned int size_y); 00155 00156 00157 private: 00163 void updateObstacles(const std::vector<Observation>& observations, std::priority_queue<CellData>& inflation_queue); 00164 00169 void raytraceFreespace(const Observation& clearing_observation); 00170 00171 inline bool worldToMap3DFloat(double wx, double wy, double wz, double& mx, double& my, double& mz){ 00172 if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_) 00173 return false; 00174 mx = ((wx - origin_x_) / xy_resolution_); 00175 my = ((wy - origin_y_) / xy_resolution_); 00176 mz = ((wz - origin_z_) / z_resolution_); 00177 00178 if(mx < size_x_ && my < size_y_ && mz < size_z_) 00179 return true; 00180 00181 return false; 00182 } 00183 00184 inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz){ 00185 if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_) 00186 return false; 00187 00188 mx = (int) ((wx - origin_x_) / xy_resolution_); 00189 my = (int) ((wy - origin_y_) / xy_resolution_); 00190 mz = (int) ((wz - origin_z_) / z_resolution_); 00191 00192 if(mx < size_x_ && my < size_y_ && mz < size_z_) 00193 return true; 00194 00195 return false; 00196 } 00197 00198 inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz){ 00199 //returns the center point of the cell 00200 wx = origin_x_ + (mx + 0.5) * xy_resolution_; 00201 wy = origin_y_ + (my + 0.5) * xy_resolution_; 00202 wz = origin_z_ + (mz + 0.5) * z_resolution_; 00203 } 00204 00205 inline double dist(double x0, double y0, double z0, double x1, double y1, double z1){ 00206 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0)); 00207 } 00208 00209 void finishConfiguration(costmap_2d::Costmap2DConfig &config); 00210 00211 protected: 00212 voxel_grid::VoxelGrid voxel_grid_; 00213 double xy_resolution_, z_resolution_, origin_z_; 00214 unsigned int unknown_threshold_, mark_threshold_, size_z_; 00215 00216 }; 00217 }; 00218 00219 #endif