Go to the documentation of this file.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
00038 #ifndef COSTMAP_2D_INFLATION_LAYER_H_
00039 #define COSTMAP_2D_INFLATION_LAYER_H_
00040
00041 #include <ros/ros.h>
00042 #include <costmap_2d/layer.h>
00043 #include <costmap_2d/layered_costmap.h>
00044 #include <costmap_2d/InflationPluginConfig.h>
00045 #include <dynamic_reconfigure/server.h>
00046 #include <queue>
00047
00048 namespace costmap_2d
00049 {
00054 class CellData
00055 {
00056 public:
00067 CellData(double d, double i, unsigned int x, unsigned int y, unsigned int sx, unsigned int sy) :
00068 distance_(d), index_(i), x_(x), y_(y), src_x_(sx), src_y_(sy)
00069 {
00070 }
00071 double distance_;
00072 unsigned int index_;
00073 unsigned int x_, y_;
00074 unsigned int src_x_, src_y_;
00075 };
00076
00081 inline bool operator<(const CellData &a, const CellData &b)
00082 {
00083 return a.distance_ > b.distance_;
00084 }
00085
00086 class InflationLayer : public Layer
00087 {
00088 public:
00089 InflationLayer();
00090
00091 virtual ~InflationLayer()
00092 {
00093 deleteKernels();
00094 if(dsrv_)
00095 delete dsrv_;
00096 }
00097
00098 virtual void onInitialize();
00099 virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, double* max_x,
00100 double* max_y);
00101 virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
00102 virtual bool isDiscretized()
00103 {
00104 return true;
00105 }
00106 virtual void matchSize();
00107
00108 virtual void reset() { onInitialize(); }
00109
00113 inline unsigned char computeCost(double distance) const
00114 {
00115 unsigned char cost = 0;
00116 if (distance == 0)
00117 cost = LETHAL_OBSTACLE;
00118 else if (distance * resolution_ <= inscribed_radius_)
00119 cost = INSCRIBED_INFLATED_OBSTACLE;
00120 else
00121 {
00122
00123 double euclidean_distance = distance * resolution_;
00124 double factor = exp(-1.0 * weight_ * (euclidean_distance - inscribed_radius_));
00125 cost = (unsigned char)((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
00126 }
00127 return cost;
00128 }
00129
00130 protected:
00131 virtual void onFootprintChanged();
00132 boost::shared_mutex* access_;
00133
00134 private:
00143 inline double distanceLookup(int mx, int my, int src_x, int src_y)
00144 {
00145 unsigned int dx = abs(mx - src_x);
00146 unsigned int dy = abs(my - src_y);
00147 return cached_distances_[dx][dy];
00148 }
00149
00158 inline unsigned char costLookup(int mx, int my, int src_x, int src_y)
00159 {
00160 unsigned int dx = abs(mx - src_x);
00161 unsigned int dy = abs(my - src_y);
00162 return cached_costs_[dx][dy];
00163 }
00164
00165 void computeCaches();
00166 void deleteKernels();
00167 void inflate_area(int min_i, int min_j, int max_i, int max_j, unsigned char* master_grid);
00168
00169 unsigned int cellDistance(double world_dist)
00170 {
00171 return layered_costmap_->getCostmap()->cellDistance(world_dist);
00172 }
00173
00174 inline void enqueue(unsigned char* grid, unsigned int index, unsigned int mx, unsigned int my, unsigned int src_x,
00175 unsigned int src_y);
00176
00177 double inflation_radius_, inscribed_radius_, weight_;
00178 unsigned int cell_inflation_radius_;
00179 unsigned int cached_cell_inflation_radius_;
00180 std::priority_queue<CellData> inflation_queue_;
00181
00182 double resolution_;
00183
00184 bool* seen_;
00185
00186 unsigned char** cached_costs_;
00187 double** cached_distances_;
00188
00189 dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig> *dsrv_;
00190 void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level);
00191
00192 bool need_reinflation_;
00193 };
00194
00195 }
00196
00197 #endif // COSTMAP_2D_INFLATION_LAYER_H_
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55