#include <footprint_layer.h>
Public Member Functions | |
virtual void | onInitialize () |
This is called at the end of initialize(). Override to implement subclass-specific initialization. | |
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 (costmap_2d::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 | ~FootprintLayer () |
Private Member Functions | |
void | publishFootprint () |
void | reconfigureCB (costmap_2d::GenericPluginConfig &config, uint32_t level) |
Private Attributes | |
dynamic_reconfigure::Server < costmap_2d::GenericPluginConfig > * | dsrv_ |
geometry_msgs::PolygonStamped | footprint_ |
Storage for polygon being published. | |
ros::Publisher | footprint_pub_ |
Definition at line 54 of file footprint_layer.h.
costmap_2d::FootprintLayer::~FootprintLayer | ( | ) | [virtual] |
Definition at line 64 of file footprint_layer.cpp.
void costmap_2d::FootprintLayer::onInitialize | ( | ) | [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 from costmap_2d::Layer.
Definition at line 48 of file footprint_layer.cpp.
void costmap_2d::FootprintLayer::publishFootprint | ( | ) | [private] |
void costmap_2d::FootprintLayer::reconfigureCB | ( | costmap_2d::GenericPluginConfig & | config, |
uint32_t | level | ||
) | [private] |
Definition at line 70 of file footprint_layer.cpp.
void costmap_2d::FootprintLayer::updateBounds | ( | double | robot_x, |
double | robot_y, | ||
double | robot_yaw, | ||
double * | min_x, | ||
double * | min_y, | ||
double * | max_x, | ||
double * | max_y | ||
) | [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 from costmap_2d::Layer.
Definition at line 75 of file footprint_layer.cpp.
void costmap_2d::FootprintLayer::updateCosts | ( | costmap_2d::Costmap2D & | master_grid, |
int | min_i, | ||
int | min_j, | ||
int | max_i, | ||
int | max_j | ||
) | [virtual] |
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
Reimplemented from costmap_2d::Layer.
Definition at line 103 of file footprint_layer.cpp.
dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>* costmap_2d::FootprintLayer::dsrv_ [private] |
Definition at line 69 of file footprint_layer.h.
geometry_msgs::PolygonStamped costmap_2d::FootprintLayer::footprint_ [private] |
Storage for polygon being published.
Definition at line 65 of file footprint_layer.h.
Definition at line 68 of file footprint_layer.h.