Nav2 Navigation Stack - jazzy  jazzy
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 };
62 
67 class Costmap2D
68 {
69  friend class CostmapTester; // Need this for gtest to work correctly
70 
71 public:
81  Costmap2D(
82  unsigned int cells_size_x, unsigned int cells_size_y, double resolution,
83  double origin_x, double origin_y, unsigned char default_value = 0);
84 
89  Costmap2D(const Costmap2D & map);
90 
95  explicit Costmap2D(const nav_msgs::msg::OccupancyGrid & map);
96 
102  Costmap2D & operator=(const Costmap2D & map);
103 
112  bool copyCostmapWindow(
113  const Costmap2D & map, double win_origin_x, double win_origin_y,
114  double win_size_x,
115  double win_size_y);
116 
128  bool copyWindow(
129  const Costmap2D & source,
130  unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn,
131  unsigned int dx0, unsigned int dy0);
132 
136  Costmap2D();
137 
141  virtual ~Costmap2D();
142 
149  unsigned char getCost(unsigned int mx, unsigned int my) const;
150 
156  unsigned char getCost(unsigned int index) const;
157 
164  void setCost(unsigned int mx, unsigned int my, unsigned char cost);
165 
173  void mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const;
174 
183  bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const;
184 
193  bool worldToMapContinuous(double wx, double wy, float & mx, float & my) const;
194 
203  void worldToMapNoBounds(double wx, double wy, int & mx, int & my) const;
204 
213  void worldToMapEnforceBounds(double wx, double wy, int & mx, int & my) const;
214 
221  inline unsigned int getIndex(unsigned int mx, unsigned int my) const
222  {
223  return my * size_x_ + mx;
224  }
225 
232  inline void indexToCells(unsigned int index, unsigned int & mx, unsigned int & my) const
233  {
234  my = index / size_x_;
235  mx = index - (my * size_x_);
236  }
237 
242  unsigned char * getCharMap() const;
243 
248  unsigned int getSizeInCellsX() const;
249 
254  unsigned int getSizeInCellsY() const;
255 
260  double getSizeInMetersX() const;
261 
266  double getSizeInMetersY() const;
267 
272  double getOriginX() const;
273 
278  double getOriginY() const;
279 
284  double getResolution() const;
285 
290  void setDefaultValue(unsigned char c)
291  {
292  default_value_ = c;
293  }
294 
299  unsigned char getDefaultValue()
300  {
301  return default_value_;
302  }
303 
311  const std::vector<geometry_msgs::msg::Point> & polygon,
312  unsigned char cost_value);
313 
319  void polygonOutlineCells(
320  const std::vector<MapLocation> & polygon,
321  std::vector<MapLocation> & polygon_cells);
322 
328  void convexFillCells(
329  const std::vector<MapLocation> & polygon,
330  std::vector<MapLocation> & polygon_cells);
331 
337  virtual void updateOrigin(double new_origin_x, double new_origin_y);
338 
343  bool saveMap(std::string file_name);
344 
348  void resizeMap(
349  unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
350  double origin_y);
351 
355  void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn);
356 
360  void resetMapToValue(
361  unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value);
362 
368  unsigned int cellDistance(double world_dist);
369 
370  // Provide a typedef to ease future code maintenance
371  typedef std::recursive_mutex mutex_t;
372  mutex_t * getMutex()
373  {
374  return access_;
375  }
376 
377 protected:
391  template<typename data_type>
393  data_type * source_map, unsigned int sm_lower_left_x,
394  unsigned int sm_lower_left_y,
395  unsigned int sm_size_x, data_type * dest_map, unsigned int dm_lower_left_x,
396  unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x,
397  unsigned int region_size_y)
398  {
399  // we'll first need to compute the starting points for each map
400  data_type * sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
401  data_type * dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
402 
403  // now, we'll copy the source map into the destination map
404  for (unsigned int i = 0; i < region_size_y; ++i) {
405  memcpy(dm_index, sm_index, region_size_x * sizeof(data_type));
406  sm_index += sm_size_x;
407  dm_index += dm_size_x;
408  }
409  }
410 
414  virtual void deleteMaps();
415 
419  virtual void resetMaps();
420 
426  virtual void initMaps(unsigned int size_x, unsigned int size_y);
427 
439  template<class ActionType>
440  inline void raytraceLine(
441  ActionType at, unsigned int x0, unsigned int y0, unsigned int x1,
442  unsigned int y1,
443  unsigned int max_length = UINT_MAX, unsigned int min_length = 0)
444  {
445  int dx_full = x1 - x0;
446  int dy_full = y1 - y0;
447 
448  // we need to chose how much to scale our dominant dimension,
449  // based on the maximum length of the line
450  double dist = std::hypot(dx_full, dy_full);
451  if (dist < min_length) {
452  return;
453  }
454 
455  unsigned int min_x0, min_y0;
456  if (dist > 0.0) {
457  // Adjust starting point and offset to start from min_length distance
458  min_x0 = (unsigned int)(x0 + dx_full / dist * min_length);
459  min_y0 = (unsigned int)(y0 + dy_full / dist * min_length);
460  } else {
461  // dist can be 0 if [x0, y0]==[x1, y1].
462  // In this case only this cell should be processed.
463  min_x0 = x0;
464  min_y0 = y0;
465  }
466  unsigned int offset = min_y0 * size_x_ + min_x0;
467 
468  int dx = x1 - min_x0;
469  int dy = y1 - min_y0;
470 
471  unsigned int abs_dx = abs(dx);
472  unsigned int abs_dy = abs(dy);
473 
474  int offset_dx = sign(dx);
475  int offset_dy = sign(dy) * size_x_;
476 
477  double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
478  // if x is dominant
479  if (abs_dx >= abs_dy) {
480  int error_y = abs_dx / 2;
481 
482  bresenham2D(
483  at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (unsigned int)(scale * abs_dx));
484  return;
485  }
486 
487  // otherwise y is dominant
488  int error_x = abs_dy / 2;
489 
490  bresenham2D(
491  at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (unsigned int)(scale * abs_dy));
492  }
493 
494 private:
499  template<class ActionType>
500  inline void bresenham2D(
501  ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b,
502  int offset_a,
503  int offset_b, unsigned int offset,
504  unsigned int max_length)
505  {
506  unsigned int end = std::min(max_length, abs_da);
507  for (unsigned int i = 0; i < end; ++i) {
508  at(offset);
509  offset += offset_a;
510  error_b += abs_db;
511  if ((unsigned int)error_b >= abs_da) {
512  offset += offset_b;
513  error_b -= abs_da;
514  }
515  }
516  at(offset);
517  }
518 
522  inline int sign(int x)
523  {
524  return x > 0 ? 1.0 : -1.0;
525  }
526 
527  mutex_t * access_;
528 
529 protected:
530  unsigned int size_x_;
531  unsigned int size_y_;
532  double resolution_;
533  double origin_x_;
534  double origin_y_;
535  unsigned char * costmap_;
536  unsigned char default_value_;
537 
538  // *INDENT-OFF* Uncrustify doesn't handle indented public/private labels
539  class MarkCell
540  {
541  public:
542  MarkCell(unsigned char * costmap, unsigned char value)
543  : costmap_(costmap), value_(value)
544  {
545  }
546  inline void operator()(unsigned int offset)
547  {
548  costmap_[offset] = value_;
549  }
550 
551  private:
552  unsigned char * costmap_;
553  unsigned char value_;
554  };
555 
557  {
558  public:
560  const Costmap2D & costmap, const unsigned char * /*char_map*/,
561  std::vector<MapLocation> & cells)
562  : costmap_(costmap), cells_(cells)
563  {
564  }
565 
566  // just push the relevant cells back onto the list
567  inline void operator()(unsigned int offset)
568  {
569  MapLocation loc;
570  costmap_.indexToCells(offset, loc.x, loc.y);
571  cells_.push_back(loc);
572  }
573 
574  private:
575  const Costmap2D & costmap_;
576  std::vector<MapLocation> & cells_;
577  };
578  // *INDENT-ON*
579 };
580 } // namespace nav2_costmap_2d
581 
582 #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:68
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:221
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:428
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:549
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:440
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:321
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:285
void setDefaultValue(unsigned char c)
Set the default background value of the costmap.
Definition: costmap_2d.hpp:290
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:392
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:445
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:544
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:343
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:399
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:529
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
Definition: costmap_2d.hpp:232
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:524
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:315
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:300
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 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:514
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:539
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:519
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:534
unsigned char getDefaultValue()
Get the default background value of the costmap.
Definition: costmap_2d.hpp:299
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