Go to the documentation of this file.
   37 #ifndef COSTMAP_2D_LAYER_H_ 
   38 #define COSTMAP_2D_LAYER_H_ 
   64   virtual void updateBounds(
double robot_x, 
double robot_y, 
double robot_yaw, 
double* min_x, 
double* min_y,
 
   65                             double* max_x, 
double* max_y) {}
 
   71   virtual void updateCosts(Costmap2D& master_grid, 
int min_i, 
int min_j, 
int max_i, 
int max_j) {}
 
   79   virtual void reset() {}
 
  119   inline const std::string& 
getName() const noexcept
 
  125   const std::vector<geometry_msgs::Point>& 
getFootprint() 
const;
 
  151 #endif  // COSTMAP_2D_LAYER_H_ 
  
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
 
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
 
void initialize(LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf)
 
virtual void activate()
Restart publishers if they've been stopped.
 
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().
 
LayeredCostmap * layered_costmap_
 
const std::string & getName() const noexcept
 
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,...
 
std::vector< geometry_msgs::Point > footprint_spec_
 
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 up...
 
const std::vector< geometry_msgs::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
 
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
 
virtual void deactivate()
Stop publishers.
 
bool isEnabled() const noexcept
getter if the current layer is enabled.
 
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17