Go to the documentation of this file.
   38 #ifndef COSTMAP_2D_COSTMAP_LAYER_H_ 
   39 #define COSTMAP_2D_COSTMAP_LAYER_H_ 
   47 class CostmapLayer : 
public Layer, 
public Costmap2D
 
   61   virtual void clearArea(
int start_x, 
int start_y, 
int end_x, 
int end_y, 
bool invert_area=
false);
 
   72   void addExtraBounds(
double mx0, 
double my0, 
double mx1, 
double my1);
 
  129   void touch(
double x, 
double y, 
double* min_x, 
double* min_y, 
double* max_x, 
double* max_y);
 
  143   void useExtraBounds(
double* min_x, 
double* min_y, 
double* max_x, 
double* max_y);
 
  151 #endif  // COSTMAP_2D_COSTMAP_LAYER_H_ 
  
void updateWithAddition(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert_area=false)
 
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
 
A 2D costmap provides a mapping between points in the world and their associated "costs".
 
void updateWithOverwrite(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)
 
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateWithTrueOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void addExtraBounds(double mx0, double my0, double mx1, double my1)
 
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17