#include <footprint.h>
Public Member Functions | |
Costmap3dLayerFootprint () | |
Polygon & | getFootprint () |
const geometry_msgs::PolygonStamped & | getFootprintMsg () const |
float | getFootprintRadius () const |
int | getRangeMax () const |
const CSpace3Cache & | getTemplate () const |
void | loadConfig (XmlRpc::XmlRpcValue config) |
void | setExpansion (const float linear_expand, const float linear_spread) |
void | setFootprint (const Polygon footprint) |
void | setMapMetaData (const costmap_cspace_msgs::MapMetaData3D &info) |
Protected Member Functions | |
void | gemerateCSpace (CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg, const UpdatedRegion ®ion) |
bool | updateChain (const bool output) |
void | updateCSpace (const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion) |
Protected Attributes | |
CSpace3Cache | cs_template_ |
geometry_msgs::PolygonStamped | footprint_ |
Polygon | footprint_p_ |
float | footprint_radius_ |
float | linear_expand_ |
float | linear_spread_ |
int | range_max_ |
Definition at line 52 of file footprint.h.
Definition at line 68 of file footprint.h.
void costmap_cspace::Costmap3dLayerFootprint::gemerateCSpace | ( | CSpace3DMsg::Ptr | map, |
const nav_msgs::OccupancyGrid::ConstPtr & | msg, | ||
const UpdatedRegion & | region | ||
) | [inline, protected] |
Definition at line 182 of file footprint.h.
Polygon& costmap_cspace::Costmap3dLayerFootprint::getFootprint | ( | ) | [inline] |
Definition at line 99 of file footprint.h.
const geometry_msgs::PolygonStamped& costmap_cspace::Costmap3dLayerFootprint::getFootprintMsg | ( | ) | const [inline] |
Definition at line 103 of file footprint.h.
float costmap_cspace::Costmap3dLayerFootprint::getFootprintRadius | ( | ) | const [inline] |
Definition at line 107 of file footprint.h.
int costmap_cspace::Costmap3dLayerFootprint::getRangeMax | ( | ) | const [inline, virtual] |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 111 of file footprint.h.
const CSpace3Cache& costmap_cspace::Costmap3dLayerFootprint::getTemplate | ( | ) | const [inline] |
Definition at line 115 of file footprint.h.
void costmap_cspace::Costmap3dLayerFootprint::loadConfig | ( | XmlRpc::XmlRpcValue | config | ) | [inline, virtual] |
Implements costmap_cspace::Costmap3dLayerBase.
Reimplemented in costmap_cspace::Costmap3dLayerPlain.
Definition at line 74 of file footprint.h.
void costmap_cspace::Costmap3dLayerFootprint::setExpansion | ( | const float | linear_expand, |
const float | linear_spread | ||
) | [inline] |
Definition at line 81 of file footprint.h.
void costmap_cspace::Costmap3dLayerFootprint::setFootprint | ( | const Polygon | footprint | ) | [inline] |
Definition at line 93 of file footprint.h.
void costmap_cspace::Costmap3dLayerFootprint::setMapMetaData | ( | const costmap_cspace_msgs::MapMetaData3D & | info | ) | [inline, virtual] |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 119 of file footprint.h.
bool costmap_cspace::Costmap3dLayerFootprint::updateChain | ( | const bool | output | ) | [inline, protected, virtual] |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 169 of file footprint.h.
void costmap_cspace::Costmap3dLayerFootprint::updateCSpace | ( | const nav_msgs::OccupancyGrid::ConstPtr & | map, |
const UpdatedRegion & | region | ||
) | [inline, protected, virtual] |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 173 of file footprint.h.
Definition at line 64 of file footprint.h.
geometry_msgs::PolygonStamped costmap_cspace::Costmap3dLayerFootprint::footprint_ [protected] |
Definition at line 59 of file footprint.h.
Definition at line 62 of file footprint.h.
float costmap_cspace::Costmap3dLayerFootprint::footprint_radius_ [protected] |
Definition at line 58 of file footprint.h.
float costmap_cspace::Costmap3dLayerFootprint::linear_expand_ [protected] |
Definition at line 60 of file footprint.h.
float costmap_cspace::Costmap3dLayerFootprint::linear_spread_ [protected] |
Definition at line 61 of file footprint.h.
int costmap_cspace::Costmap3dLayerFootprint::range_max_ [protected] |
Definition at line 65 of file footprint.h.