Go to the documentation of this file.
   38 #ifndef COSTMAP_2D_COSTMAP_2D_H_ 
   39 #define COSTMAP_2D_COSTMAP_2D_H_ 
   43 #include <geometry_msgs/Point.h> 
   44 #include <boost/thread.hpp> 
   73   Costmap2D(
unsigned int cells_size_x, 
unsigned int cells_size_y, 
double resolution,
 
   74             double origin_x, 
double origin_y, 
unsigned char default_value = 0);
 
  116   unsigned char getCost(
unsigned int mx, 
unsigned int my) 
const;
 
  124   void setCost(
unsigned int mx, 
unsigned int my, 
unsigned char cost);
 
  133   void mapToWorld(
unsigned int mx, 
unsigned int my, 
double& wx, 
double& wy) 
const;
 
  143   bool worldToMap(
double wx, 
double wy, 
unsigned int& mx, 
unsigned int& my) 
const;
 
  171   inline unsigned int getIndex(
unsigned int mx, 
unsigned int my)
 const 
  182   inline void indexToCells(
unsigned int index, 
unsigned int& mx, 
unsigned int& my)
 const 
  252   bool setConvexPolygonCost(
const std::vector<geometry_msgs::Point>& polygon, 
unsigned char cost_value);
 
  259   void polygonOutlineCells(
const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells);
 
  266   void convexFillCells(
const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells);
 
  273   virtual void updateOrigin(
double new_origin_x, 
double new_origin_y);
 
  279   bool saveMap(std::string file_name);
 
  281   void resizeMap(
unsigned int size_x, 
unsigned int size_y, 
double resolution, 
double origin_x,
 
  284   void resetMap(
unsigned int x0, 
unsigned int y0, 
unsigned int xn, 
unsigned int yn);
 
  294   typedef boost::recursive_mutex 
mutex_t;
 
  314   template<
typename data_type>
 
  315     void copyMapRegion(data_type* source_map, 
unsigned int sm_lower_left_x, 
unsigned int sm_lower_left_y,
 
  316                        unsigned int sm_size_x, data_type* dest_map, 
unsigned int dm_lower_left_x,
 
  317                        unsigned int dm_lower_left_y, 
unsigned int dm_size_x, 
unsigned int region_size_x,
 
  318                        unsigned int region_size_y)
 
  321       data_type* sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
 
  322       data_type* dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
 
  325       for (
unsigned int i = 0; i < region_size_y; ++i)
 
  327         memcpy(dm_index, sm_index, region_size_x * 
sizeof(data_type));
 
  328         sm_index += sm_size_x;
 
  329         dm_index += dm_size_x;
 
  348   virtual void initMaps(
unsigned int size_x, 
unsigned int size_y);
 
  359   template<
class ActionType>
 
  360     inline void raytraceLine(ActionType at, 
unsigned int x0, 
unsigned int y0, 
unsigned int x1, 
unsigned int y1,
 
  361                              unsigned int max_length = UINT_MAX)
 
  366       unsigned int abs_dx = abs(dx);
 
  367       unsigned int abs_dy = abs(dy);
 
  369       int offset_dx = 
sign(dx);
 
  372       unsigned int offset = y0 * 
size_x_ + x0;
 
  375       double dist = hypot(dx, dy);
 
  376       double scale = (dist == 0.0) ? 1.0 : std::min(1.0, max_length / dist);
 
  379       if (abs_dx >= abs_dy)
 
  381         int error_y = abs_dx / 2;
 
  382         bresenham2D(at, abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (
unsigned int)(scale * abs_dx));
 
  387       int error_x = abs_dy / 2;
 
  388       bresenham2D(at, abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (
unsigned int)(scale * abs_dy));
 
  395   template<
class ActionType>
 
  396     inline void bresenham2D(ActionType at, 
unsigned int abs_da, 
unsigned int abs_db, 
int error_b, 
int offset_a,
 
  397                             int offset_b, 
unsigned int offset, 
unsigned int max_length)
 
  399       unsigned int end = std::min(max_length, abs_da);
 
  400       for (
unsigned int i = 0; i < end; ++i)
 
  405         if ((
unsigned int)error_b >= abs_da)
 
  414   inline int sign(
int x)
 
  416     return x > 0 ? 1.0 : -1.0;
 
  432     MarkCell(
unsigned char* costmap, 
unsigned char value) :
 
  445   class PolygonOutlineCells
 
  464     std::vector<MapLocation>& 
cells_;
 
  469 #endif  // COSTMAP_2D_COSTMAP_2D_H 
  
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
virtual void initMaps(unsigned int size_x, unsigned int size_y)
Initializes the costmap, static_map, and markers data structures.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
unsigned char default_value_
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
const Costmap2D & costmap_
virtual ~Costmap2D()
Destructor.
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.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
double getOriginX() const
Accessor for the x origin of the costmap.
unsigned char getDefaultValue()
friend class CostmapTester
Costmap2D()
Default constructor.
void polygonOutlineCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that make up the outline of a polygon.
Costmap2D & operator=(const Costmap2D &map)
Overloaded assignment operator.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
void operator()(unsigned int offset)
void operator()(unsigned int offset)
bool saveMap(std::string file_name)
Save the costmap out to a pgm file.
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
PolygonOutlineCells(const Costmap2D &costmap, const unsigned char *char_map, std::vector< MapLocation > &cells)
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
const unsigned char * char_map_
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
void worldToMapEnforceBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates, constraining results to legal bounds.
double getOriginY() const
Accessor for the y origin of the costmap.
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 cellDistance(double world_dist)
Given distance in the world... convert it to cells.
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
virtual void deleteMaps()
Deletes the costmap, static_map, and markers data structures.
void setDefaultValue(unsigned char c)
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.
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.
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.
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
void bresenham2D(ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset, unsigned int max_length)
A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step.
boost::recursive_mutex mutex_t
void worldToMapNoBounds(double wx, double wy, int &mx, int &my) const
Convert from world coordinates to map coordinates without checking for legal bounds.
void convexFillCells(const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
Get the map cells that fill a convex polygon.
MarkCell(unsigned char *costmap, unsigned char value)
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17