Instantiates different layer plugins and aggregates them into one score.
More...
#include <layered_costmap.h>
|
void | addPlugin (boost::shared_ptr< Layer > plugin) |
|
void | getBounds (unsigned int *x0, unsigned int *xn, unsigned int *y0, unsigned int *yn) |
|
double | getCircumscribedRadius () |
| The radius of a circle centered at the origin of the robot which just surrounds all points on the robot's footprint. More...
|
|
Costmap2D * | getCostmap () |
|
const std::vector< geometry_msgs::Point > & | getFootprint () |
| Returns the latest footprint stored with setFootprint(). More...
|
|
std::string | getGlobalFrameID () const |
|
double | getInscribedRadius () |
| The radius of a circle centered at the origin of the robot which is just within all points and edges of the robot's footprint. More...
|
|
std::vector< boost::shared_ptr< Layer > > * | getPlugins () |
|
void | getUpdatedBounds (double &minx, double &miny, double &maxx, double &maxy) |
|
bool | isCurrent () |
|
bool | isInitialized () |
|
bool | isRolling () |
|
bool | isSizeLocked () |
|
bool | isTrackingUnknown () |
|
| LayeredCostmap (std::string global_frame, bool rolling_window, bool track_unknown) |
| Constructor for a costmap. More...
|
|
void | resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false) |
|
void | setFootprint (const std::vector< geometry_msgs::Point > &footprint_spec) |
| Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintChanged() in all layers. More...
|
|
void | updateMap (double robot_x, double robot_y, double robot_yaw) |
| Update the underlying costmap with new data. If you want to update the map outside of the update loop that runs, you can call this. More...
|
|
| ~LayeredCostmap () |
| Destructor. More...
|
|
Instantiates different layer plugins and aggregates them into one score.
Definition at line 55 of file layered_costmap.h.
costmap_2d::LayeredCostmap::LayeredCostmap |
( |
std::string |
global_frame, |
|
|
bool |
rolling_window, |
|
|
bool |
track_unknown |
|
) |
| |
costmap_2d::LayeredCostmap::~LayeredCostmap |
( |
| ) |
|
void costmap_2d::LayeredCostmap::getBounds |
( |
unsigned int * |
x0, |
|
|
unsigned int * |
xn, |
|
|
unsigned int * |
y0, |
|
|
unsigned int * |
yn |
|
) |
| |
|
inline |
double costmap_2d::LayeredCostmap::getCircumscribedRadius |
( |
| ) |
|
|
inline |
The radius of a circle centered at the origin of the robot which just surrounds all points on the robot's footprint.
This is updated by setFootprint().
Definition at line 148 of file layered_costmap.h.
Costmap2D* costmap_2d::LayeredCostmap::getCostmap |
( |
| ) |
|
|
inline |
std::string costmap_2d::LayeredCostmap::getGlobalFrameID |
( |
| ) |
const |
|
inline |
double costmap_2d::LayeredCostmap::getInscribedRadius |
( |
| ) |
|
|
inline |
The radius of a circle centered at the origin of the robot which is just within all points and edges of the robot's footprint.
This is updated by setFootprint().
Definition at line 155 of file layered_costmap.h.
void costmap_2d::LayeredCostmap::getUpdatedBounds |
( |
double & |
minx, |
|
|
double & |
miny, |
|
|
double & |
maxx, |
|
|
double & |
maxy |
|
) |
| |
|
inline |
bool costmap_2d::LayeredCostmap::isCurrent |
( |
| ) |
|
bool costmap_2d::LayeredCostmap::isInitialized |
( |
| ) |
|
|
inline |
bool costmap_2d::LayeredCostmap::isRolling |
( |
| ) |
|
|
inline |
bool costmap_2d::LayeredCostmap::isSizeLocked |
( |
| ) |
|
|
inline |
bool costmap_2d::LayeredCostmap::isTrackingUnknown |
( |
| ) |
|
|
inline |
void costmap_2d::LayeredCostmap::resizeMap |
( |
unsigned int |
size_x, |
|
|
unsigned int |
size_y, |
|
|
double |
resolution, |
|
|
double |
origin_x, |
|
|
double |
origin_y, |
|
|
bool |
size_locked = false |
|
) |
| |
void costmap_2d::LayeredCostmap::setFootprint |
( |
const std::vector< geometry_msgs::Point > & |
footprint_spec | ) |
|
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintChanged() in all layers.
Definition at line 173 of file layered_costmap.cpp.
void costmap_2d::LayeredCostmap::updateMap |
( |
double |
robot_x, |
|
|
double |
robot_y, |
|
|
double |
robot_yaw |
|
) |
| |
Update the underlying costmap with new data. If you want to update the map outside of the update loop that runs, you can call this.
Definition at line 95 of file layered_costmap.cpp.
unsigned int costmap_2d::LayeredCostmap::bx0_ |
|
private |
unsigned int costmap_2d::LayeredCostmap::bxn_ |
|
private |
unsigned int costmap_2d::LayeredCostmap::by0_ |
|
private |
unsigned int costmap_2d::LayeredCostmap::byn_ |
|
private |
double costmap_2d::LayeredCostmap::circumscribed_radius_ |
|
private |
Costmap2D costmap_2d::LayeredCostmap::costmap_ |
|
private |
bool costmap_2d::LayeredCostmap::current_ |
|
private |
<
Whether or not the costmap should roll with the robot
Definition at line 163 of file layered_costmap.h.
std::string costmap_2d::LayeredCostmap::global_frame_ |
|
private |
bool costmap_2d::LayeredCostmap::initialized_ |
|
private |
double costmap_2d::LayeredCostmap::inscribed_radius_ |
|
private |
double costmap_2d::LayeredCostmap::maxx_ |
|
private |
double costmap_2d::LayeredCostmap::maxy_ |
|
private |
double costmap_2d::LayeredCostmap::minx_ |
|
private |
double costmap_2d::LayeredCostmap::miny_ |
|
private |
bool costmap_2d::LayeredCostmap::rolling_window_ |
|
private |
bool costmap_2d::LayeredCostmap::size_locked_ |
|
private |
The documentation for this class was generated from the following files:
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:42