Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
costmap_2d::CostmapLayer Class Reference

#include <costmap_layer.h>

Inheritance diagram for costmap_2d::CostmapLayer:
Inheritance graph
[legend]

Public Member Functions

void addExtraBounds (double mx0, double my0, double mx1, double my1)
 
virtual void clearArea (int start_x, int start_y, int end_x, int end_y, bool invert_area=false)
 
 CostmapLayer ()
 
bool isDiscretized ()
 
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap. More...
 
- Public Member Functions inherited from costmap_2d::Layer
virtual void activate ()
 Restart publishers if they've been stopped. More...
 
virtual void deactivate ()
 Stop publishers. More...
 
const std::vector< geometry_msgs::Point > & getFootprint () const
 Convenience function for layered_costmap_->getFootprint(). More...
 
const std::string & getName () const noexcept
 
void initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf)
 
bool isCurrent () const
 Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More...
 
bool isEnabled () const noexcept
 getter if the current layer is enabled. More...
 
 Layer ()
 
virtual void onFootprintChanged ()
 LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. More...
 
virtual void reset ()
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds. More...
 
virtual void updateCosts (Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 Actually update the underlying costmap, only within the bounds calculated during UpdateBounds(). More...
 
virtual ~Layer ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
unsigned int cellDistance (double world_dist)
 Given distance in the world... convert it to cells. More...
 
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that fill a convex polygon. More...
 
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. More...
 
 Costmap2D ()
 Default constructor. More...
 
 Costmap2D (const Costmap2D &map)
 Copy constructor for a costmap, creates a copy efficiently. More...
 
 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. More...
 
unsigned char * getCharMap () const
 Will return a pointer to the underlying unsigned char array used as the costmap. More...
 
unsigned char getCost (unsigned int mx, unsigned int my) const
 Get the cost of a cell in the costmap. More...
 
unsigned char getDefaultValue ()
 
unsigned int getIndex (unsigned int mx, unsigned int my) const
 Given two map coordinates... compute the associated index. More...
 
mutex_tgetMutex ()
 
double getOriginX () const
 Accessor for the x origin of the costmap. More...
 
double getOriginY () const
 Accessor for the y origin of the costmap. More...
 
double getResolution () const
 Accessor for the resolution of the costmap. More...
 
unsigned int getSizeInCellsX () const
 Accessor for the x size of the costmap in cells. More...
 
unsigned int getSizeInCellsY () const
 Accessor for the y size of the costmap in cells. More...
 
double getSizeInMetersX () const
 Accessor for the x size of the costmap in meters. More...
 
double getSizeInMetersY () const
 Accessor for the y size of the costmap in meters. More...
 
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 Given an index... compute the associated map coordinates. More...
 
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 Convert from map coordinates to world coordinates. More...
 
Costmap2Doperator= (const Costmap2D &map)
 Overloaded assignment operator. More...
 
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that make up the outline of a polygon. More...
 
void resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
 
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
 
bool saveMap (std::string file_name)
 Save the costmap out to a pgm file. More...
 
bool setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
 Sets the cost of a convex polygon to a desired value. More...
 
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 Set the cost of a cell in the costmap. More...
 
void setDefaultValue (unsigned char c)
 
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. More...
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 Convert from world coordinates to map coordinates. More...
 
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates, constraining results to legal bounds. More...
 
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates without checking for legal bounds. More...
 
virtual ~Costmap2D ()
 Destructor. More...
 

Protected Member Functions

void touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateWithAddition (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithMax (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithTrueOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y)
 
- Protected Member Functions inherited from costmap_2d::Layer
virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization. More...
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
template<typename data_type >
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. More...
 
virtual void deleteMaps ()
 Deletes the costmap, static_map, and markers data structures. More...
 
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 Initializes the costmap, static_map, and markers data structures. More...
 
template<class ActionType >
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. More...
 
virtual void resetMaps ()
 Resets the costmap and static_map to be unknown space. More...
 

Protected Attributes

bool has_extra_bounds_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf2_ros::Buffertf_
 
- Protected Attributes inherited from costmap_2d::Costmap2D
unsigned char * costmap_
 
unsigned char default_value_
 
double origin_x_
 
double origin_y_
 
double resolution_
 
unsigned int size_x_
 
unsigned int size_y_
 

Private Attributes

double extra_max_x_
 
double extra_max_y_
 
double extra_min_x_
 
double extra_min_y_
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 

Detailed Description

Definition at line 83 of file costmap_layer.h.

Constructor & Destructor Documentation

◆ CostmapLayer()

costmap_2d::CostmapLayer::CostmapLayer ( )
inline

Definition at line 122 of file costmap_layer.h.

Member Function Documentation

◆ addExtraBounds()

void costmap_2d::CostmapLayer::addExtraBounds ( double  mx0,
double  my0,
double  mx1,
double  my1 
)

If an external source changes values in the costmap, it should call this method with the area that it changed to ensure that the costmap includes this region as well.

Parameters
mx0Minimum x value of the bounding box
my0Minimum y value of the bounding box
mx1Maximum x value of the bounding box
my1Maximum y value of the bounding box

Definition at line 38 of file costmap_layer.cpp.

◆ clearArea()

void costmap_2d::CostmapLayer::clearArea ( int  start_x,
int  start_y,
int  end_x,
int  end_y,
bool  invert_area = false 
)
virtual

Definition at line 21 of file costmap_layer.cpp.

◆ isDiscretized()

bool costmap_2d::CostmapLayer::isDiscretized ( )
inline

Definition at line 126 of file costmap_layer.h.

◆ matchSize()

void costmap_2d::CostmapLayer::matchSize ( )
virtual

Implement this to make this layer match the size of the parent costmap.

Reimplemented from costmap_2d::Layer.

Reimplemented in costmap_2d::VoxelLayer, and costmap_2d::StaticLayer.

Definition at line 14 of file costmap_layer.cpp.

◆ touch()

void costmap_2d::CostmapLayer::touch ( double  x,
double  y,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
protected

Updates the bounding box specified in the parameters to include the location (x,y)

Parameters
xx-coordinate to include
yy-coordinate to include
min_xbounding box
min_ybounding box
max_xbounding box
max_ybounding box

Definition at line 6 of file costmap_layer.cpp.

◆ updateWithAddition()

void costmap_2d::CostmapLayer::updateWithAddition ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
protected

Definition at line 127 of file costmap_layer.cpp.

◆ updateWithMax()

void costmap_2d::CostmapLayer::updateWithMax ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
protected

Definition at line 63 of file costmap_layer.cpp.

◆ updateWithOverwrite()

void costmap_2d::CostmapLayer::updateWithOverwrite ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
protected

Definition at line 108 of file costmap_layer.cpp.

◆ updateWithTrueOverwrite()

void costmap_2d::CostmapLayer::updateWithTrueOverwrite ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
protected

Definition at line 89 of file costmap_layer.cpp.

◆ useExtraBounds()

void costmap_2d::CostmapLayer::useExtraBounds ( double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
protected

Definition at line 47 of file costmap_layer.cpp.

Member Data Documentation

◆ extra_max_x_

double costmap_2d::CostmapLayer::extra_max_x_
private

Definition at line 219 of file costmap_layer.h.

◆ extra_max_y_

double costmap_2d::CostmapLayer::extra_max_y_
private

Definition at line 219 of file costmap_layer.h.

◆ extra_min_x_

double costmap_2d::CostmapLayer::extra_min_x_
private

Definition at line 219 of file costmap_layer.h.

◆ extra_min_y_

double costmap_2d::CostmapLayer::extra_min_y_
private

Definition at line 219 of file costmap_layer.h.

◆ has_extra_bounds_

bool costmap_2d::CostmapLayer::has_extra_bounds_
protected

Definition at line 216 of file costmap_layer.h.


The documentation for this class was generated from the following files:


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17