#include <footprint.h>
Definition at line 53 of file footprint.h.
costmap_cspace::Costmap3dLayerFootprint::Costmap3dLayerFootprint |
( |
| ) |
|
|
inline |
void costmap_cspace::Costmap3dLayerFootprint::clearTravelableArea |
( |
CSpace3DMsg::Ptr |
map, |
|
|
const nav_msgs::OccupancyGrid::ConstPtr & |
msg |
|
) |
| |
|
inlineprotected |
virtual void costmap_cspace::Costmap3dLayerFootprint::generateCSpace |
( |
CSpace3DMsg::Ptr |
map, |
|
|
const nav_msgs::OccupancyGrid::ConstPtr & |
msg, |
|
|
const UpdatedRegion & |
region |
|
) |
| |
|
inlineprotectedvirtual |
void costmap_cspace::Costmap3dLayerFootprint::generateSpecifiedCSpace |
( |
CSpace3DMsg::Ptr |
map, |
|
|
const nav_msgs::OccupancyGrid::ConstPtr & |
msg, |
|
|
const size_t |
yaw |
|
) |
| |
|
inlineprotected |
Polygon& costmap_cspace::Costmap3dLayerFootprint::getFootprint |
( |
| ) |
|
|
inline |
const geometry_msgs::PolygonStamped& costmap_cspace::Costmap3dLayerFootprint::getFootprintMsg |
( |
| ) |
const |
|
inline |
float costmap_cspace::Costmap3dLayerFootprint::getFootprintRadius |
( |
| ) |
const |
|
inline |
int costmap_cspace::Costmap3dLayerFootprint::getRangeMax |
( |
| ) |
const |
|
inlinevirtual |
const CSpace3Cache& costmap_cspace::Costmap3dLayerFootprint::getTemplate |
( |
| ) |
const |
|
inline |
void costmap_cspace::Costmap3dLayerFootprint::setExpansion |
( |
const float |
linear_expand, |
|
|
const float |
linear_spread |
|
) |
| |
|
inline |
void costmap_cspace::Costmap3dLayerFootprint::setFootprint |
( |
const Polygon |
footprint | ) |
|
|
inline |
void costmap_cspace::Costmap3dLayerFootprint::setKeepUnknown |
( |
const bool |
keep_unknown | ) |
|
|
inline |
void costmap_cspace::Costmap3dLayerFootprint::setMapMetaData |
( |
const costmap_cspace_msgs::MapMetaData3D & |
info | ) |
|
|
inlinevirtual |
bool costmap_cspace::Costmap3dLayerFootprint::updateChain |
( |
const bool |
output | ) |
|
|
inlineprotectedvirtual |
void costmap_cspace::Costmap3dLayerFootprint::updateCSpace |
( |
const nav_msgs::OccupancyGrid::ConstPtr & |
map, |
|
|
const UpdatedRegion & |
region |
|
) |
| |
|
inlineprotectedvirtual |
CSpace3Cache costmap_cspace::Costmap3dLayerFootprint::cs_template_ |
|
protected |
geometry_msgs::PolygonStamped costmap_cspace::Costmap3dLayerFootprint::footprint_ |
|
protected |
Polygon costmap_cspace::Costmap3dLayerFootprint::footprint_p_ |
|
protected |
float costmap_cspace::Costmap3dLayerFootprint::footprint_radius_ |
|
protected |
bool costmap_cspace::Costmap3dLayerFootprint::keep_unknown_ |
|
protected |
float costmap_cspace::Costmap3dLayerFootprint::linear_expand_ |
|
protected |
float costmap_cspace::Costmap3dLayerFootprint::linear_spread_ |
|
protected |
int costmap_cspace::Costmap3dLayerFootprint::range_max_ |
|
protected |
std::vector<bool> costmap_cspace::Costmap3dLayerFootprint::unknown_buf_ |
|
protected |
The documentation for this class was generated from the following file: