00001
00002
00003
00004
00005
00006
00007
00008
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 #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
00051 namespace costmap_2d {
00056 class VoxelCostmap2D : public Costmap2D {
00057 public:
00081 VoxelCostmap2D(unsigned int cells_size_x, unsigned int cells_size_y, unsigned int cells_size_z,
00082 double xy_resolution, double z_resolution, double origin_x, double origin_y, double origin_z = 0.0, double inscribed_radius = 0.0,
00083 double circumscribed_radius = 0.0, double inflation_radius = 0.0, double obstacle_range = 0.0,
00084 double raytrace_range = 0.0, double weight = 25.0,
00085 const std::vector<unsigned char>& static_data = std::vector<unsigned char>(0), unsigned char lethal_threshold = 0,
00086 unsigned int unknown_threshold = 0, unsigned int mark_threshold = 0, unsigned char unknown_cost_value = 0);
00087
00091 ~VoxelCostmap2D();
00092
00100 void resetMapOutsideWindow(double wx, double wy, double w_size_x, double w_size_y);
00101
00107 void updateOrigin(double new_origin_x, double new_origin_y);
00108
00117 virtual void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info = false);
00118
00123 void getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud);
00124
00125 void getVoxelGridMessage(VoxelGrid& grid);
00126
00127 static inline void mapToWorld3D(const unsigned int mx, const unsigned int my, const unsigned int mz,
00128 const double origin_x, const double origin_y, const double origin_z,
00129 const double x_resolution, const double y_resolution, const double z_resolution,
00130 double& wx, double& wy, double& wz){
00131
00132 wx = origin_x + (mx + 0.5) * x_resolution;
00133 wy = origin_y + (my + 0.5) * y_resolution;
00134 wz = origin_z + (mz + 0.5) * z_resolution;
00135 }
00136
00137 protected:
00141 virtual void resetMaps();
00142
00148 virtual void initMaps(unsigned int size_x, unsigned int size_y);
00149
00150
00151 private:
00157 void updateObstacles(const std::vector<Observation>& observations, std::priority_queue<CellData>& inflation_queue);
00158
00163 void raytraceFreespace(const Observation& clearing_observation);
00164
00165 inline bool worldToMap3DFloat(double wx, double wy, double wz, double& mx, double& my, double& mz){
00166 if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
00167 return false;
00168 mx = ((wx - origin_x_) / xy_resolution_);
00169 my = ((wy - origin_y_) / xy_resolution_);
00170 mz = ((wz - origin_z_) / z_resolution_);
00171
00172 if(mx < size_x_ && my < size_y_ && mz < size_z_)
00173 return true;
00174
00175 return false;
00176 }
00177
00178 inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz){
00179 if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
00180 return false;
00181
00182 mx = (int) ((wx - origin_x_) / xy_resolution_);
00183 my = (int) ((wy - origin_y_) / xy_resolution_);
00184 mz = (int) ((wz - origin_z_) / z_resolution_);
00185
00186 if(mx < size_x_ && my < size_y_ && mz < size_z_)
00187 return true;
00188
00189 return false;
00190 }
00191
00192 inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz){
00193
00194 wx = origin_x_ + (mx + 0.5) * xy_resolution_;
00195 wy = origin_y_ + (my + 0.5) * xy_resolution_;
00196 wz = origin_z_ + (mz + 0.5) * z_resolution_;
00197 }
00198
00199 inline double dist(double x0, double y0, double z0, double x1, double y1, double z1){
00200 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
00201 }
00202
00203 protected:
00204 voxel_grid::VoxelGrid voxel_grid_;
00205 double xy_resolution_, z_resolution_, origin_z_;
00206 unsigned int unknown_threshold_, mark_threshold_, size_z_;
00207
00208 };
00209 };
00210
00211 #endif