38#ifndef EASYNAV_COSTMAP_COMMON__COSTMAP_2D_HPP_
39#define EASYNAV_COSTMAP_COMMON__COSTMAP_2D_HPP_
50#include "geometry_msgs/msg/point.hpp"
51#include "nav_msgs/msg/occupancy_grid.hpp"
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);
111 bool inBounds(
unsigned int x,
unsigned int y)
const;
122 const Costmap2D & map,
double win_origin_x,
double win_origin_y,
149 unsigned int sx0,
unsigned int sy0,
unsigned int sxn,
unsigned int syn,
150 unsigned int dx0,
unsigned int dy0);
168 unsigned char getCost(
unsigned int mx,
unsigned int my)
const;
175 unsigned char getCost(
unsigned int index)
const;
183 void setCost(
unsigned int mx,
unsigned int my,
unsigned char cost);
192 void mapToWorld(
unsigned int mx,
unsigned int my,
double & wx,
double & wy)
const;
211 bool worldToMap(
double wx,
double wy,
unsigned int & mx,
unsigned int & my)
const;
249 inline unsigned int getIndex(
unsigned int mx,
unsigned int my)
const
260 inline void indexToCells(
unsigned int index,
unsigned int & mx,
unsigned int & my)
const
339 const std::vector<geometry_msgs::msg::Point> & polygon,
340 unsigned char cost_value);
349 const std::vector<geometry_msgs::msg::Point> & polygon,
350 std::vector<MapLocation> & polygon_map_region);
358 const std::vector<MapLocation> & polygon_map_region,
359 unsigned char new_cost_value);
366 const std::vector<MapLocation> & polygon_map_region);
374 const std::vector<MapLocation> & polygon,
375 std::vector<MapLocation> & polygon_cells);
383 const std::vector<MapLocation> & polygon,
384 std::vector<MapLocation> & polygon_cells);
391 virtual void updateOrigin(
double new_origin_x,
double new_origin_y);
397 unsigned int size_x,
unsigned int size_y,
double resolution,
double origin_x,
403 void resetMap(
unsigned int x0,
unsigned int y0,
unsigned int xn,
unsigned int yn);
409 unsigned int x0,
unsigned int y0,
unsigned int xn,
unsigned int yn,
unsigned char value);
439 template<
typename data_type>
441 data_type * source_map,
unsigned int sm_lower_left_x,
442 unsigned int sm_lower_left_y,
443 unsigned int sm_size_x, data_type * dest_map,
unsigned int dm_lower_left_x,
444 unsigned int dm_lower_left_y,
unsigned int dm_size_x,
unsigned int region_size_x,
445 unsigned int region_size_y)
448 data_type * sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
449 data_type * dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
452 for (
unsigned int i = 0; i < region_size_y; ++i) {
453 memcpy(dm_index, sm_index, region_size_x *
sizeof(data_type));
454 sm_index += sm_size_x;
455 dm_index += dm_size_x;
474 virtual void initMaps(
unsigned int size_x,
unsigned int size_y);
487 template<
class ActionType>
489 ActionType at,
unsigned int x0,
unsigned int y0,
unsigned int x1,
491 unsigned int max_length = UINT_MAX,
unsigned int min_length = 0)
493 int dx_full = x1 - x0;
494 int dy_full = y1 - y0;
498 double dist = std::hypot(dx_full, dy_full);
499 if (dist < min_length) {
503 unsigned int min_x0, min_y0;
506 min_x0 = (
unsigned int)(x0 + dx_full / dist * min_length);
507 min_y0 = (
unsigned int)(y0 + dy_full / dist * min_length);
514 unsigned int offset = min_y0 *
size_x_ + min_x0;
516 int dx = x1 - min_x0;
517 int dy = y1 - min_y0;
519 unsigned int abs_dx = abs(dx);
520 unsigned int abs_dy = abs(dy);
522 int offset_dx = sign(dx);
523 int offset_dy = sign(dy) *
size_x_;
525 double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
527 if (abs_dx >= abs_dy) {
528 int error_y = abs_dx / 2;
531 at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (
unsigned int)(scale * abs_dx));
536 int error_x = abs_dy / 2;
539 at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (
unsigned int)(scale * abs_dy));
547 template<
class ActionType>
548 inline void bresenham2D(
549 ActionType at,
unsigned int abs_da,
unsigned int abs_db,
int error_b,
551 int offset_b,
unsigned int offset,
552 unsigned int max_length)
554 unsigned int end = std::min(max_length, abs_da);
555 for (
unsigned int i = 0; i < end; ++i) {
559 if ((
unsigned int)error_b >= abs_da) {
570 inline int sign(
int x)
572 return x > 0 ? 1.0 : -1.0;
590 MarkCell(
unsigned char * costmap,
unsigned char value)
591 : costmap_(costmap), value_(value)
596 costmap_[offset] = value_;
601 unsigned char value_;
608 const Costmap2D & costmap,
const unsigned char * ,
609 std::vector<MapLocation> & cells)
610 : costmap_(costmap), cells_(cells)
618 costmap_.indexToCells(offset, loc.
x, loc.
y);
619 loc.
cost = costmap_.getCost(loc.
x, loc.
y);
620 cells_.push_back(loc);
625 std::vector<MapLocation> & cells_;
MarkCell(unsigned char *costmap, unsigned char value)
Definition costmap_2d.hpp:590
PolygonOutlineCells(const Costmap2D &costmap, const unsigned char *, std::vector< MapLocation > &cells)
Definition costmap_2d.hpp:607
Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
Constructor for a costmap.
Definition costmap_2d.cpp:54
MarkCell(unsigned char *costmap, unsigned char value)
Definition costmap_2d.hpp:590
void operator()(unsigned int offset)
Definition costmap_2d.hpp:594
PolygonOutlineCells(const Costmap2D &costmap, const unsigned char *, std::vector< MapLocation > &cells)
Definition costmap_2d.hpp:607
void operator()(unsigned int offset)
Definition costmap_2d.hpp:615
Costmap2D()
Default constructor.
Definition costmap_2d.cpp:272
void polygonOutlineCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that make up the outline of a polygon.
Definition costmap_2d.cpp:495
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition costmap_2d.cpp:295
bool inBounds(unsigned int x, unsigned int y) const
Checks whether a given cell coordinate is within the bounds of the costmap.
Definition costmap_2d.cpp:284
double getResolution() const
Accessor for the resolution of the costmap.
Definition costmap_2d.cpp:612
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
Definition costmap_2d.hpp:318
unsigned int size_x_
Definition costmap_2d.hpp:578
Costmap2D & operator=(const Costmap2D &map)
Overloaded assignment operator.
Definition costmap_2d.cpp:238
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.
Definition costmap_2d.cpp:189
void mapToWorldNoBounds(int mx, int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates with no bounds checking.
Definition costmap_2d.cpp:321
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
Definition costmap_2d.hpp:260
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition costmap_2d.cpp:597
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition costmap_2d.cpp:289
virtual void initMaps(unsigned int size_x, unsigned int size_y)
Initializes the costmap, static_map, and markers data structures.
Definition costmap_2d.cpp:106
Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
Constructor for a costmap.
Definition costmap_2d.cpp:54
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.
Definition costmap_2d.cpp:150
virtual void deleteMaps()
Deletes the costmap, static_map, and markers data structures.
Definition costmap_2d.cpp:98
void restoreMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region)
Restores the corresponding map region using given map region.
Definition costmap_2d.cpp:465
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition costmap_2d.cpp:582
double getOriginX() const
Accessor for the x origin of the costmap.
Definition costmap_2d.cpp:602
double resolution_
Definition costmap_2d.hpp:580
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition costmap_2d.cpp:310
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
Definition costmap_2d.cpp:363
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition costmap_2d.cpp:129
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.
Definition costmap_2d.hpp:488
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
Definition costmap_2d.cpp:342
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location....
Definition costmap_2d.cpp:385
bool getMapRegionOccupiedByPolygon(const std::vector< geometry_msgs::msg::Point > &polygon, std::vector< MapLocation > &polygon_map_region)
Gets the map region occupied by polygon.
Definition costmap_2d.cpp:473
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition costmap_2d.cpp:327
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition costmap_2d.cpp:587
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition costmap_2d.hpp:249
unsigned char * costmap_
Definition costmap_2d.hpp:583
friend class CostmapTester
Definition costmap_2d.hpp:70
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.
Definition costmap_2d.hpp:440
unsigned char getDefaultValue()
Get the default background value of the costmap.
Definition costmap_2d.hpp:327
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
Definition costmap_2d.cpp:357
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition costmap_2d.cpp:300
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
Definition costmap_2d.cpp:115
void toOccupancyGridMsg(nav_msgs::msg::OccupancyGrid &msg) const
Converts the current costmap into a nav_msgs::msg::OccupancyGrid message.
Definition costmap_2d.cpp:213
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.
Definition costmap_2d.cpp:140
std::recursive_mutex mutex_t
Definition costmap_2d.hpp:419
unsigned int size_y_
Definition costmap_2d.hpp:579
void setMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region, unsigned char new_cost_value)
Sets the given map region to desired value.
Definition costmap_2d.cpp:456
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.
Definition costmap_2d.cpp:441
double origin_y_
Definition costmap_2d.hpp:582
double getOriginY() const
Accessor for the y origin of the costmap.
Definition costmap_2d.cpp:607
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition costmap_2d.cpp:315
virtual ~Costmap2D()
Destructor.
Definition costmap_2d.cpp:278
mutex_t * getMutex()
Definition costmap_2d.hpp:420
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
Definition costmap_2d.cpp:135
double origin_x_
Definition costmap_2d.hpp:581
unsigned char default_value_
Definition costmap_2d.hpp:584
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition costmap_2d.cpp:592
void convexFillCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that fill a convex polygon.
Definition costmap_2d.cpp:512
Provides a mapping for often used cost values.
Definition cost_values.hpp:41
Definition costmap_2d.hpp:58
unsigned char cost
Definition costmap_2d.hpp:61
unsigned int x
Definition costmap_2d.hpp:59
unsigned int y
Definition costmap_2d.hpp:60