#include <layer.h>
Public Member Functions | |
virtual void | activate () |
Restart publishers if they've been stopped. | |
virtual void | deactivate () |
Stop publishers. | |
const std::vector < geometry_msgs::Point > & | getFootprint () const |
Convenience function for layered_costmap_->getFootprint(). | |
std::string | getName () const |
void | initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *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. | |
Layer () | |
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()). Override to be notified of changes to the robot's footprint. | |
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. | |
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 | ~Layer () |
Protected Member Functions | |
virtual void | onInitialize () |
This is called at the end of initialize(). Override to implement subclass-specific initialization. | |
Protected Attributes | |
bool | current_ |
bool | enabled_ |
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class. | |
LayeredCostmap * | layered_costmap_ |
std::string | name_ |
tf::TransformListener * | tf_ |
Private Attributes | |
std::vector< geometry_msgs::Point > | footprint_spec_ |
virtual costmap_2d::Layer::~Layer | ( | ) | [inline, virtual] |
virtual void costmap_2d::Layer::activate | ( | ) | [inline, virtual] |
Restart publishers if they've been stopped.
Reimplemented in costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.
virtual void costmap_2d::Layer::deactivate | ( | ) | [inline, virtual] |
Stop publishers.
Reimplemented in costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.
const std::vector< geometry_msgs::Point > & costmap_2d::Layer::getFootprint | ( | ) | const |
Convenience function for layered_costmap_->getFootprint().
std::string costmap_2d::Layer::getName | ( | ) | const [inline] |
void costmap_2d::Layer::initialize | ( | LayeredCostmap * | parent, |
std::string | name, | ||
tf::TransformListener * | tf | ||
) |
bool costmap_2d::Layer::isCurrent | ( | ) | const [inline] |
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.
A layer's current state should be managed by the protected variable current_.
virtual void costmap_2d::Layer::matchSize | ( | ) | [inline, virtual] |
Implement this to make this layer match the size of the parent costmap.
Reimplemented in costmap_2d::InflationLayer, costmap_2d::VoxelLayer, costmap_2d::StaticLayer, and costmap_2d::CostmapLayer.
virtual void costmap_2d::Layer::onFootprintChanged | ( | ) | [inline, virtual] |
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint.
Reimplemented in costmap_2d::InflationLayer.
virtual void costmap_2d::Layer::onInitialize | ( | ) | [inline, protected, virtual] |
This is called at the end of initialize(). Override to implement subclass-specific initialization.
tf_, name_, and layered_costmap_ will all be set already when this is called.
Reimplemented in costmap_2d::InflationLayer, costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.
virtual void costmap_2d::Layer::reset | ( | ) | [inline, virtual] |
Reimplemented in costmap_2d::InflationLayer, costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.
virtual void costmap_2d::Layer::updateBounds | ( | double | robot_x, |
double | robot_y, | ||
double | robot_yaw, | ||
double * | min_x, | ||
double * | min_y, | ||
double * | max_x, | ||
double * | max_y | ||
) | [inline, virtual] |
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.
For more details, see "Layered Costmaps for Context-Sensitive Navigation", by Lu et. Al, IROS 2014.
Reimplemented in costmap_2d::InflationLayer, costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.
virtual void costmap_2d::Layer::updateCosts | ( | Costmap2D & | master_grid, |
int | min_i, | ||
int | min_j, | ||
int | max_i, | ||
int | max_j | ||
) | [inline, virtual] |
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
Reimplemented in costmap_2d::InflationLayer, costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.
bool costmap_2d::Layer::current_ [protected] |
bool costmap_2d::Layer::enabled_ [protected] |
std::vector<geometry_msgs::Point> costmap_2d::Layer::footprint_spec_ [private] |
LayeredCostmap* costmap_2d::Layer::layered_costmap_ [protected] |
std::string costmap_2d::Layer::name_ [protected] |
tf::TransformListener* costmap_2d::Layer::tf_ [protected] |