37 #ifndef COSTMAP_2D_LAYER_H_ 38 #define COSTMAP_2D_LAYER_H_ 65 virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
66 double* max_x,
double* max_y) {}
108 const std::vector<geometry_msgs::Point>&
getFootprint()
const;
134 #endif // COSTMAP_2D_LAYER_H_ LayeredCostmap * layered_costmap_
void initialize(LayeredCostmap *parent, std::string name, tf::TransformListener *tf)
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
std::string getName() const
tf::TransformListener * tf_
std::vector< geometry_msgs::Point > footprint_spec_
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
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...
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().
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.
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
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...
const std::vector< geometry_msgs::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
A 2D costmap provides a mapping between points in the world and their associated "costs".
virtual void deactivate()
Stop publishers.
Instantiates different layer plugins and aggregates them into one score.
virtual void activate()
Restart publishers if they've been stopped.