45 Costmap2D::Costmap2D(
unsigned int cells_size_x,
unsigned int cells_size_y,
double resolution,
46 double origin_x,
double origin_y,
unsigned char default_value) :
47 size_x_(cells_size_x), size_y_(cells_size_y), resolution_(resolution), origin_x_(origin_x),
48 origin_y_(origin_y), costmap_(NULL), default_value_(default_value)
60 boost::unique_lock<mutex_t> lock(*
access_);
67 boost::unique_lock<mutex_t> lock(*
access_);
69 costmap_ =
new unsigned char[size_x * size_y];
73 double origin_x,
double origin_y)
89 boost::unique_lock<mutex_t> lock(*
access_);
95 boost::unique_lock<mutex_t> lock(*(
access_));
96 unsigned int len = xn - x0;
115 unsigned int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
116 if (!map.
worldToMap(win_origin_x, win_origin_y, lower_left_x, lower_left_y)
117 || !map.
worldToMap(win_origin_x + win_size_x, win_origin_y + win_size_y, upper_right_x, upper_right_y))
123 size_x_ = upper_right_x - lower_left_x;
124 size_y_ = upper_right_y - lower_left_y;
184 return (
unsigned int)cells_dist;
263 int cell_ox, cell_oy;
269 double new_grid_ox, new_grid_oy;
278 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
279 lower_left_x =
min(
max(cell_ox, 0), size_x);
280 lower_left_y =
min(
max(cell_oy, 0), size_y);
281 upper_right_x =
min(
max(cell_ox + size_x, 0), size_x);
282 upper_right_y =
min(
max(cell_oy + size_y, 0), size_y);
284 unsigned int cell_size_x = upper_right_x - lower_left_x;
285 unsigned int cell_size_y = upper_right_y - lower_left_y;
288 unsigned char* local_map =
new unsigned char[cell_size_x * cell_size_y];
301 int start_x = lower_left_x - cell_ox;
302 int start_y = lower_left_y - cell_oy;
314 std::vector<MapLocation> map_polygon;
315 for (
unsigned int i = 0; i < polygon.size(); ++i)
323 map_polygon.push_back(loc);
326 std::vector<MapLocation> polygon_cells;
332 for (
unsigned int i = 0; i < polygon_cells.size(); ++i)
334 unsigned int index =
getIndex(polygon_cells[i].
x, polygon_cells[i].
y);
343 for (
unsigned int i = 0; i < polygon.size() - 1; ++i)
345 raytraceLine(cell_gatherer, polygon[i].
x, polygon[i].
y, polygon[i + 1].x, polygon[i + 1].y);
347 if (!polygon.empty())
349 unsigned int last_index = polygon.size() - 1;
351 raytraceLine(cell_gatherer, polygon[last_index].
x, polygon[last_index].
y, polygon[0].x, polygon[0].y);
358 if (polygon.size() < 3)
367 while (i < polygon_cells.size() - 1)
369 if (polygon_cells[i].
x > polygon_cells[i + 1].
x)
371 swap = polygon_cells[i];
372 polygon_cells[i] = polygon_cells[i + 1];
373 polygon_cells[i + 1] = swap;
385 unsigned int min_x = polygon_cells[0].
x;
386 unsigned int max_x = polygon_cells[polygon_cells.size() - 1].x;
389 for (
unsigned int x = min_x;
x <= max_x; ++
x)
391 if (i >= polygon_cells.size() - 1)
394 if (polygon_cells[i].
y < polygon_cells[i + 1].
y)
396 min_pt = polygon_cells[i];
397 max_pt = polygon_cells[i + 1];
401 min_pt = polygon_cells[i + 1];
402 max_pt = polygon_cells[i];
406 while (i < polygon_cells.size() && polygon_cells[i].x ==
x)
408 if (polygon_cells[i].
y < min_pt.
y)
409 min_pt = polygon_cells[i];
410 else if (polygon_cells[i].
y > max_pt.
y)
411 max_pt = polygon_cells[i];
417 for (
unsigned int y = min_pt.
y;
y < max_pt.
y; ++
y)
421 polygon_cells.push_back(pt);
463 FILE *fp = fopen(file_name.c_str(),
"w");
471 for (
unsigned int iy = 0; iy <
size_y_; iy++)
473 for (
unsigned int ix = 0; ix <
size_x_; ix++)
475 unsigned char cost =
getCost(ix, iy);
476 fprintf(fp,
"%d ", cost);
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
virtual void initMaps(unsigned int size_x, unsigned int size_y)
Initializes the costmap, static_map, and markers data structures.
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
double getOriginX() const
Accessor for the x origin of the costmap.
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
virtual void deleteMaps()
Deletes the costmap, static_map, and markers data structures.
TFSIMD_FORCE_INLINE const tfScalar & y() const
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as 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 raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
Raytrace a line and apply some action at each step.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
boost::recursive_mutex mutex_t
void convexFillCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that fill a convex polygon.
bool saveMap(std::string file_name)
Save the costmap out to a pgm file.
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
void polygonOutlineCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that make up the outline of a polygon.
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
double min(double a, double b)
double getOriginY() const
Accessor for the y origin of the costmap.
Costmap2D & operator=(const Costmap2D &map)
Overloaded assignment operator.
virtual ~Costmap2D()
Destructor.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
unsigned char default_value_
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.
Costmap2D()
Default constructor.
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.
A 2D costmap provides a mapping between points in the world and their associated "costs".
double getResolution() const
Accessor for the resolution of the costmap.
void swap(scoped_ptr< T > &, scoped_ptr< T > &)
double max(double a, double b)
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)