38 #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_2D_HPP_
50 #include "geometry_msgs/msg/point.hpp"
51 #include "nav_msgs/msg/occupancy_grid.hpp"
70 friend class CostmapTester;
83 unsigned int cells_size_x,
unsigned int cells_size_y,
double resolution,
84 double origin_x,
double origin_y,
unsigned char default_value = 0);
96 explicit Costmap2D(
const nav_msgs::msg::OccupancyGrid & map);
114 const Costmap2D & map,
double win_origin_x,
double win_origin_y,
131 unsigned int sx0,
unsigned int sy0,
unsigned int sxn,
unsigned int syn,
132 unsigned int dx0,
unsigned int dy0);
150 unsigned char getCost(
unsigned int mx,
unsigned int my)
const;
157 unsigned char getCost(
unsigned int index)
const;
165 void setCost(
unsigned int mx,
unsigned int my,
unsigned char cost);
174 void mapToWorld(
unsigned int mx,
unsigned int my,
double & wx,
double & wy)
const;
193 bool worldToMap(
double wx,
double wy,
unsigned int & mx,
unsigned int & my)
const;
231 inline unsigned int getIndex(
unsigned int mx,
unsigned int my)
const
233 return my * size_x_ + mx;
242 inline void indexToCells(
unsigned int index,
unsigned int & mx,
unsigned int & my)
const
244 my = index / size_x_;
245 mx = index - (my * size_x_);
311 return default_value_;
321 const std::vector<geometry_msgs::msg::Point> & polygon,
322 unsigned char cost_value);
331 const std::vector<geometry_msgs::msg::Point> & polygon,
332 std::vector<MapLocation> & polygon_map_region);
340 const std::vector<MapLocation> & polygon_map_region,
341 unsigned char new_cost_value);
348 const std::vector<MapLocation> & polygon_map_region);
356 const std::vector<MapLocation> & polygon,
357 std::vector<MapLocation> & polygon_cells);
365 const std::vector<MapLocation> & polygon,
366 std::vector<MapLocation> & polygon_cells);
373 virtual void updateOrigin(
double new_origin_x,
double new_origin_y);
379 bool saveMap(std::string file_name);
385 unsigned int size_x,
unsigned int size_y,
double resolution,
double origin_x,
391 void resetMap(
unsigned int x0,
unsigned int y0,
unsigned int xn,
unsigned int yn);
397 unsigned int x0,
unsigned int y0,
unsigned int xn,
unsigned int yn,
unsigned char value);
407 typedef std::recursive_mutex mutex_t;
427 template<
typename data_type>
429 data_type * source_map,
unsigned int sm_lower_left_x,
430 unsigned int sm_lower_left_y,
431 unsigned int sm_size_x, data_type * dest_map,
unsigned int dm_lower_left_x,
432 unsigned int dm_lower_left_y,
unsigned int dm_size_x,
unsigned int region_size_x,
433 unsigned int region_size_y)
436 data_type * sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
437 data_type * dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
440 for (
unsigned int i = 0; i < region_size_y; ++i) {
441 memcpy(dm_index, sm_index, region_size_x *
sizeof(data_type));
442 sm_index += sm_size_x;
443 dm_index += dm_size_x;
462 virtual void initMaps(
unsigned int size_x,
unsigned int size_y);
475 template<
class ActionType>
477 ActionType at,
unsigned int x0,
unsigned int y0,
unsigned int x1,
479 unsigned int max_length = UINT_MAX,
unsigned int min_length = 0)
481 int dx_full = x1 - x0;
482 int dy_full = y1 - y0;
486 double dist = std::hypot(dx_full, dy_full);
487 if (dist < min_length) {
491 unsigned int min_x0, min_y0;
494 min_x0 = (
unsigned int)(x0 + dx_full / dist * min_length);
495 min_y0 = (
unsigned int)(y0 + dy_full / dist * min_length);
502 unsigned int offset = min_y0 * size_x_ + min_x0;
504 int dx = x1 - min_x0;
505 int dy = y1 - min_y0;
507 unsigned int abs_dx = abs(dx);
508 unsigned int abs_dy = abs(dy);
510 int offset_dx = sign(dx);
511 int offset_dy = sign(dy) * size_x_;
513 double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
515 if (abs_dx >= abs_dy) {
516 int error_y = abs_dx / 2;
519 at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (
unsigned int)(scale * abs_dx));
524 int error_x = abs_dy / 2;
527 at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (
unsigned int)(scale * abs_dy));
535 template<
class ActionType>
536 inline void bresenham2D(
537 ActionType at,
unsigned int abs_da,
unsigned int abs_db,
int error_b,
539 int offset_b,
unsigned int offset,
540 unsigned int max_length)
542 unsigned int end = std::min(max_length, abs_da);
543 for (
unsigned int i = 0; i < end; ++i) {
547 if ((
unsigned int)error_b >= abs_da) {
558 inline int sign(
int x)
560 return x > 0 ? 1.0 : -1.0;
566 unsigned int size_x_;
567 unsigned int size_y_;
571 unsigned char * costmap_;
572 unsigned char default_value_;
578 MarkCell(
unsigned char * costmap,
unsigned char value)
579 : costmap_(costmap), value_(value)
582 inline void operator()(
unsigned int offset)
584 costmap_[offset] = value_;
588 unsigned char * costmap_;
589 unsigned char value_;
596 const Costmap2D & costmap,
const unsigned char * ,
597 std::vector<MapLocation> & cells)
598 : costmap_(costmap), cells_(cells)
603 inline void operator()(
unsigned int offset)
606 costmap_.indexToCells(offset, loc.x, loc.y);
607 loc.cost = costmap_.getCost(loc.x, loc.y);
608 cells_.push_back(loc);
613 std::vector<MapLocation> & cells_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
void resetMapToValue(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value)
Reset the costmap in bounds to a value.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
virtual ~Costmap2D()
Destructor.
void polygonOutlineCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that make up the outline of a polygon.
void mapToWorldNoBounds(int mx, int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates with no bounds checking.
virtual void deleteMaps()
Deletes the costmap, static_map, and markers data structures.
bool saveMap(std::string file_name)
Save the costmap out to a pgm file.
bool copyWindow(const Costmap2D &source, unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn, unsigned int dx0, unsigned int dy0)
Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap.
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX, unsigned int min_length=0)
Raytrace a line and apply some action at each step.
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
void copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
Copy a region of a source map into a destination map.
void convexFillCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that fill a convex polygon.
double getResolution() const
Accessor for the resolution of the costmap.
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
Costmap2D()
Default constructor.
bool setConvexPolygonCost(const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
void setMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region, unsigned char new_cost_value)
Sets the given map region to desired value.
void restoreMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region)
Restores the corresponding map region using given map region.
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
virtual void initMaps(unsigned int size_x, unsigned int size_y)
Initializes the costmap, static_map, and markers data structures.
bool getMapRegionOccupiedByPolygon(const std::vector< geometry_msgs::msg::Point > &polygon, std::vector< MapLocation > &polygon_map_region)
Gets the map region occupied by polygon.
bool copyCostmapWindow(const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
Turn this costmap into a copy of a window of a costmap passed in.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
double getOriginY() const
Accessor for the y origin of the costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
double getOriginX() const
Accessor for the x origin of the costmap.
unsigned char getDefaultValue()
Get the default background value of the costmap.
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Costmap2D & operator=(const Costmap2D &map)
Overloaded assignment operator.