Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_2d.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_2D_HPP_
40 
41 #include <string.h>
42 #include <stdio.h>
43 #include <limits.h>
44 #include <algorithm>
45 #include <cmath>
46 #include <string>
47 #include <vector>
48 #include <queue>
49 #include <mutex>
50 #include "geometry_msgs/msg/point.hpp"
51 #include "nav_msgs/msg/occupancy_grid.hpp"
52 
53 namespace nav2_costmap_2d
54 {
55 
56 // convenient for storing x/y point pairs
58 {
59  unsigned int x;
60  unsigned int y;
61  unsigned char cost;
62 };
63 
68 class Costmap2D
69 {
70  friend class CostmapTester; // Need this for gtest to work correctly
71 
72 public:
82  Costmap2D(
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);
85 
90  Costmap2D(const Costmap2D & map);
91 
96  explicit Costmap2D(const nav_msgs::msg::OccupancyGrid & map);
97 
103  Costmap2D & operator=(const Costmap2D & map);
104 
113  bool copyCostmapWindow(
114  const Costmap2D & map, double win_origin_x, double win_origin_y,
115  double win_size_x,
116  double win_size_y);
117 
129  bool copyWindow(
130  const Costmap2D & source,
131  unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn,
132  unsigned int dx0, unsigned int dy0);
133 
137  Costmap2D();
138 
142  virtual ~Costmap2D();
143 
150  unsigned char getCost(unsigned int mx, unsigned int my) const;
151 
157  unsigned char getCost(unsigned int index) const;
158 
165  void setCost(unsigned int mx, unsigned int my, unsigned char cost);
166 
174  void mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const;
175 
183  void mapToWorldNoBounds(int mx, int my, double & wx, double & wy) const;
184 
193  bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const;
194 
203  bool worldToMapContinuous(double wx, double wy, float & mx, float & my) const;
204 
213  void worldToMapNoBounds(double wx, double wy, int & mx, int & my) const;
214 
223  void worldToMapEnforceBounds(double wx, double wy, int & mx, int & my) const;
224 
231  inline unsigned int getIndex(unsigned int mx, unsigned int my) const
232  {
233  return my * size_x_ + mx;
234  }
235 
242  inline void indexToCells(unsigned int index, unsigned int & mx, unsigned int & my) const
243  {
244  my = index / size_x_;
245  mx = index - (my * size_x_);
246  }
247 
252  unsigned char * getCharMap() const;
253 
258  unsigned int getSizeInCellsX() const;
259 
264  unsigned int getSizeInCellsY() const;
265 
270  double getSizeInMetersX() const;
271 
276  double getSizeInMetersY() const;
277 
282  double getOriginX() const;
283 
288  double getOriginY() const;
289 
294  double getResolution() const;
295 
300  void setDefaultValue(unsigned char c)
301  {
302  default_value_ = c;
303  }
304 
309  unsigned char getDefaultValue()
310  {
311  return default_value_;
312  }
313 
321  const std::vector<geometry_msgs::msg::Point> & polygon,
322  unsigned char cost_value);
323 
331  const std::vector<geometry_msgs::msg::Point> & polygon,
332  std::vector<MapLocation> & polygon_map_region);
333 
340  const std::vector<MapLocation> & polygon_map_region,
341  unsigned char new_cost_value);
342 
348  const std::vector<MapLocation> & polygon_map_region);
349 
355  void polygonOutlineCells(
356  const std::vector<MapLocation> & polygon,
357  std::vector<MapLocation> & polygon_cells);
358 
364  void convexFillCells(
365  const std::vector<MapLocation> & polygon,
366  std::vector<MapLocation> & polygon_cells);
367 
373  virtual void updateOrigin(double new_origin_x, double new_origin_y);
374 
379  bool saveMap(std::string file_name);
380 
384  void resizeMap(
385  unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
386  double origin_y);
387 
391  void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn);
392 
396  void resetMapToValue(
397  unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value);
398 
404  unsigned int cellDistance(double world_dist);
405 
406  // Provide a typedef to ease future code maintenance
407  typedef std::recursive_mutex mutex_t;
408  mutex_t * getMutex()
409  {
410  return access_;
411  }
412 
413 protected:
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)
434  {
435  // we'll first need to compute the starting points for each map
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);
438 
439  // now, we'll copy the source map into the destination map
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;
444  }
445  }
446 
450  virtual void deleteMaps();
451 
455  virtual void resetMaps();
456 
462  virtual void initMaps(unsigned int size_x, unsigned int size_y);
463 
475  template<class ActionType>
476  inline void raytraceLine(
477  ActionType at, unsigned int x0, unsigned int y0, unsigned int x1,
478  unsigned int y1,
479  unsigned int max_length = UINT_MAX, unsigned int min_length = 0)
480  {
481  int dx_full = x1 - x0;
482  int dy_full = y1 - y0;
483 
484  // we need to chose how much to scale our dominant dimension,
485  // based on the maximum length of the line
486  double dist = std::hypot(dx_full, dy_full);
487  if (dist < min_length) {
488  return;
489  }
490 
491  unsigned int min_x0, min_y0;
492  if (dist > 0.0) {
493  // Adjust starting point and offset to start from min_length distance
494  min_x0 = (unsigned int)(x0 + dx_full / dist * min_length);
495  min_y0 = (unsigned int)(y0 + dy_full / dist * min_length);
496  } else {
497  // dist can be 0 if [x0, y0]==[x1, y1].
498  // In this case only this cell should be processed.
499  min_x0 = x0;
500  min_y0 = y0;
501  }
502  unsigned int offset = min_y0 * size_x_ + min_x0;
503 
504  int dx = x1 - min_x0;
505  int dy = y1 - min_y0;
506 
507  unsigned int abs_dx = abs(dx);
508  unsigned int abs_dy = abs(dy);
509 
510  int offset_dx = sign(dx);
511  int offset_dy = sign(dy) * size_x_;
512 
513  double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
514  // if x is dominant
515  if (abs_dx >= abs_dy) {
516  int error_y = abs_dx / 2;
517 
518  bresenham2D(
519  at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (unsigned int)(scale * abs_dx));
520  return;
521  }
522 
523  // otherwise y is dominant
524  int error_x = abs_dy / 2;
525 
526  bresenham2D(
527  at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (unsigned int)(scale * abs_dy));
528  }
529 
530 private:
535  template<class ActionType>
536  inline void bresenham2D(
537  ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b,
538  int offset_a,
539  int offset_b, unsigned int offset,
540  unsigned int max_length)
541  {
542  unsigned int end = std::min(max_length, abs_da);
543  for (unsigned int i = 0; i < end; ++i) {
544  at(offset);
545  offset += offset_a;
546  error_b += abs_db;
547  if ((unsigned int)error_b >= abs_da) {
548  offset += offset_b;
549  error_b -= abs_da;
550  }
551  }
552  at(offset);
553  }
554 
558  inline int sign(int x)
559  {
560  return x > 0 ? 1.0 : -1.0;
561  }
562 
563  mutex_t * access_;
564 
565 protected:
566  unsigned int size_x_;
567  unsigned int size_y_;
568  double resolution_;
569  double origin_x_;
570  double origin_y_;
571  unsigned char * costmap_;
572  unsigned char default_value_;
573 
574  // *INDENT-OFF* Uncrustify doesn't handle indented public/private labels
575  class MarkCell
576  {
577  public:
578  MarkCell(unsigned char * costmap, unsigned char value)
579  : costmap_(costmap), value_(value)
580  {
581  }
582  inline void operator()(unsigned int offset)
583  {
584  costmap_[offset] = value_;
585  }
586 
587  private:
588  unsigned char * costmap_;
589  unsigned char value_;
590  };
591 
593  {
594  public:
596  const Costmap2D & costmap, const unsigned char * /*char_map*/,
597  std::vector<MapLocation> & cells)
598  : costmap_(costmap), cells_(cells)
599  {
600  }
601 
602  // just push the relevant cells back onto the list
603  inline void operator()(unsigned int offset)
604  {
605  MapLocation loc;
606  costmap_.indexToCells(offset, loc.x, loc.y);
607  loc.cost = costmap_.getCost(loc.x, loc.y);
608  cells_.push_back(loc);
609  }
610 
611  private:
612  const Costmap2D & costmap_;
613  std::vector<MapLocation> & cells_;
614  };
615  // *INDENT-ON*
616 };
617 } // namespace nav2_costmap_2d
618 
619 #endif // NAV2_COSTMAP_2D__COSTMAP_2D_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:279
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Reset the costmap in bounds.
Definition: costmap_2d.cpp:130
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:231
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:135
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:110
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
virtual ~Costmap2D()
Destructor.
Definition: costmap_2d.cpp:247
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:459
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:285
virtual void deleteMaps()
Deletes the costmap, static_map, and markers data structures.
Definition: costmap_2d.cpp:93
bool saveMap(std::string file_name)
Save the costmap out to a pgm file.
Definition: costmap_2d.cpp:581
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:184
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:476
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:327
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:291
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
Definition: costmap_2d.hpp:300
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:428
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:476
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
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.
Definition: costmap_2d.cpp:349
Costmap2D()
Default constructor.
Definition: costmap_2d.cpp:241
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:405
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:561
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
Definition: costmap_2d.hpp:242
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:556
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:420
void restoreMapRegionOccupiedByPolygon(const std::vector< MapLocation > &polygon_map_region)
Restores the corresponding map region using given map region.
Definition: costmap_2d.cpp:429
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:321
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:306
virtual void initMaps(unsigned int size_x, unsigned int size_y)
Initializes the costmap, static_map, and markers data structures.
Definition: costmap_2d.cpp:101
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:437
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:145
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:124
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:571
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:566
unsigned char getDefaultValue()
Get the default background value of the costmap.
Definition: costmap_2d.hpp:309
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:274
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:253
Costmap2D & operator=(const Costmap2D &map)
Overloaded assignment operator.
Definition: costmap_2d.cpp:207