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_COSTMAP_2D_H_
00039 #define COSTMAP_COSTMAP_2D_H_
00040
00041 #include <vector>
00042 #include <queue>
00043 #include <geometry_msgs/Point.h>
00044 #include <boost/thread.hpp>
00045
00046 namespace costmap_2d
00047 {
00048
00049
00050 struct MapLocation
00051 {
00052 unsigned int x;
00053 unsigned int y;
00054 };
00055
00060 class Costmap2D
00061 {
00062 friend class CostmapTester;
00063 public:
00073 Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution,
00074 double origin_x, double origin_y, unsigned char default_value = 0);
00075
00080 Costmap2D(const Costmap2D& map);
00081
00087 Costmap2D& operator=(const Costmap2D& map);
00088
00097 bool copyCostmapWindow(const Costmap2D& map, double win_origin_x, double win_origin_y, double win_size_x,
00098 double win_size_y);
00099
00103 Costmap2D();
00104
00108 virtual ~Costmap2D();
00109
00116 unsigned char getCost(unsigned int mx, unsigned int my) const;
00117
00124 void setCost(unsigned int mx, unsigned int my, unsigned char cost);
00125
00133 void mapToWorld(unsigned int mx, unsigned int my, double& wx, double& wy) const;
00134
00143 bool worldToMap(double wx, double wy, unsigned int& mx, unsigned int& my) const;
00144
00153 void worldToMapNoBounds(double wx, double wy, int& mx, int& my) const;
00154
00163 void worldToMapEnforceBounds(double wx, double wy, int& mx, int& my) const;
00164
00171 inline unsigned int getIndex(unsigned int mx, unsigned int my) const
00172 {
00173 return my * size_x_ + mx;
00174 }
00175
00182 inline void indexToCells(unsigned int index, unsigned int& mx, unsigned int& my) const
00183 {
00184 my = index / size_x_;
00185 mx = index - (my * size_x_);
00186 }
00187
00192 unsigned char* getCharMap() const;
00193
00198 unsigned int getSizeInCellsX() const;
00199
00204 unsigned int getSizeInCellsY() const;
00205
00210 double getSizeInMetersX() const;
00211
00216 double getSizeInMetersY() const;
00217
00222 double getOriginX() const;
00223
00228 double getOriginY() const;
00229
00234 double getResolution() const;
00235
00236 void setDefaultValue(unsigned char c)
00237 {
00238 default_value_ = c;
00239 }
00240
00241 unsigned char getDefaultValue()
00242 {
00243 return default_value_;
00244 }
00245
00252 bool setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value);
00253
00259 void polygonOutlineCells(const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells);
00260
00266 void convexFillCells(const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells);
00267
00273 virtual void updateOrigin(double new_origin_x, double new_origin_y);
00274
00279 bool saveMap(std::string file_name);
00280
00281 void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
00282 double origin_y);
00283
00284 void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn);
00285
00291 unsigned int cellDistance(double world_dist);
00292
00293 boost::shared_mutex* getLock()
00294 {
00295 return access_;
00296 }
00297
00298 protected:
00312 template<typename data_type>
00313 void copyMapRegion(data_type* source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y,
00314 unsigned int sm_size_x, data_type* dest_map, unsigned int dm_lower_left_x,
00315 unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x,
00316 unsigned int region_size_y)
00317 {
00318
00319 data_type* sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
00320 data_type* dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
00321
00322
00323 for (unsigned int i = 0; i < region_size_y; ++i)
00324 {
00325 memcpy(dm_index, sm_index, region_size_x * sizeof(data_type));
00326 sm_index += sm_size_x;
00327 dm_index += dm_size_x;
00328 }
00329 }
00330
00334 virtual void deleteMaps();
00335
00339 virtual void resetMaps();
00340
00346 virtual void initMaps(unsigned int size_x, unsigned int size_y);
00347
00357 template<class ActionType>
00358 inline void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1,
00359 unsigned int max_length = UINT_MAX)
00360 {
00361 int dx = x1 - x0;
00362 int dy = y1 - y0;
00363
00364 unsigned int abs_dx = abs(dx);
00365 unsigned int abs_dy = abs(dy);
00366
00367 int offset_dx = sign(dx);
00368 int offset_dy = sign(dy) * size_x_;
00369
00370 unsigned int offset = y0 * size_x_ + x0;
00371
00372
00373 double dist = hypot(dx, dy);
00374 double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
00375
00376
00377 if (abs_dx >= abs_dy)
00378 {
00379 int error_y = abs_dx / 2;
00380 bresenham2D(at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (unsigned int)(scale * abs_dx));
00381 return;
00382 }
00383
00384
00385 int error_x = abs_dy / 2;
00386 bresenham2D(at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (unsigned int)(scale * abs_dy));
00387
00388 }
00389
00390 private:
00394 template<class ActionType>
00395 inline void bresenham2D(ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a,
00396 int offset_b, unsigned int offset, unsigned int max_length)
00397 {
00398 unsigned int end = std::min(max_length, abs_da);
00399 for (unsigned int i = 0; i < end; ++i)
00400 {
00401 at(offset);
00402 offset += offset_a;
00403 error_b += abs_db;
00404 if ((unsigned int)error_b >= abs_da)
00405 {
00406 offset += offset_b;
00407 error_b -= abs_da;
00408 }
00409 }
00410 at(offset);
00411 }
00412
00413 inline int sign(int x)
00414 {
00415 return x > 0 ? 1.0 : -1.0;
00416 }
00417
00418 boost::shared_mutex* access_;
00419 protected:
00420 unsigned int size_x_;
00421 unsigned int size_y_;
00422 double resolution_;
00423 double origin_x_;
00424 double origin_y_;
00425 unsigned char* costmap_;
00426 unsigned char default_value_;
00427
00428 class MarkCell
00429 {
00430 public:
00431 MarkCell(unsigned char* costmap, unsigned char value) :
00432 costmap_(costmap), value_(value)
00433 {
00434 }
00435 inline void operator()(unsigned int offset)
00436 {
00437 costmap_[offset] = value_;
00438 }
00439 private:
00440 unsigned char* costmap_;
00441 unsigned char value_;
00442 };
00443
00444 class PolygonOutlineCells
00445 {
00446 public:
00447 PolygonOutlineCells(const Costmap2D& costmap, const unsigned char* char_map, std::vector<MapLocation>& cells) :
00448 costmap_(costmap), char_map_(char_map), cells_(cells)
00449 {
00450 }
00451
00452
00453 inline void operator()(unsigned int offset)
00454 {
00455 MapLocation loc;
00456 costmap_.indexToCells(offset, loc.x, loc.y);
00457 cells_.push_back(loc);
00458 }
00459
00460 private:
00461 const Costmap2D& costmap_;
00462 const unsigned char* char_map_;
00463 std::vector<MapLocation>& cells_;
00464 };
00465 };
00466 }
00467
00468 #endif