#include <footprint.h>

Public Types | |
| using | Ptr = std::shared_ptr< Costmap3dLayerFootprint > |
Public Types inherited from costmap_cspace::Costmap3dLayerBase | |
| using | Ptr = std::shared_ptr< Costmap3dLayerBase > |
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) |
Public Member Functions inherited from costmap_cspace::Costmap3dLayerBase | |
| Costmap3dLayerBase () | |
| int | getAngularGrid () const |
| CSpace3DMsg::Ptr | getMap () |
| CSpace3DMsg::Ptr | getMapOverlay () |
| void | processMapOverlay (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
| void | setAngleResolution (const int ang_resolution) |
| void | setBaseMap (const nav_msgs::OccupancyGrid::ConstPtr &base_map) |
| void | setChild (Costmap3dLayerBase::Ptr child) |
| void | setMap (CSpace3DMsg::Ptr map) |
| void | setOverlayMode (const MapOverlayMode overlay_mode) |
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 Member Functions inherited from costmap_cspace::Costmap3dLayerBase | |
| void | setBaseMapChain () |
| bool | updateChainEntry (const UpdatedRegion ®ion, bool output=true) |
Protected Attributes | |
| CSpace3Cache | cs_template_ |
| geometry_msgs::PolygonStamped | footprint_ |
| Polygon | footprint_p_ |
| float | footprint_radius_ |
| float | linear_expand_ |
| float | linear_spread_ |
| int | range_max_ |
Protected Attributes inherited from costmap_cspace::Costmap3dLayerBase | |
| int | ang_grid_ |
| Costmap3dLayerBase::Ptr | child_ |
| CSpace3DMsg::Ptr | map_ |
| CSpace3DMsg::Ptr | map_overlay_ |
| nav_msgs::OccupancyGrid::ConstPtr | map_updated_ |
| MapOverlayMode | overlay_mode_ |
| UpdatedRegion | region_ |
| UpdatedRegion | region_prev_ |
| bool | root_ |
Definition at line 48 of file footprint.h.
| using costmap_cspace::Costmap3dLayerFootprint::Ptr = std::shared_ptr<Costmap3dLayerFootprint> |
Definition at line 51 of file footprint.h.
|
inline |
Definition at line 64 of file footprint.h.
|
inlineprotected |
Definition at line 178 of file footprint.h.
|
inline |
Definition at line 95 of file footprint.h.
|
inline |
Definition at line 99 of file footprint.h.
|
inline |
Definition at line 103 of file footprint.h.
|
inlinevirtual |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 107 of file footprint.h.
|
inline |
Definition at line 111 of file footprint.h.
|
inlinevirtual |
Implements costmap_cspace::Costmap3dLayerBase.
Reimplemented in costmap_cspace::Costmap3dLayerPlain.
Definition at line 70 of file footprint.h.
|
inline |
Definition at line 77 of file footprint.h.
|
inline |
Definition at line 89 of file footprint.h.
|
inlinevirtual |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 115 of file footprint.h.
|
inlineprotectedvirtual |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 165 of file footprint.h.
|
inlineprotectedvirtual |
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 169 of file footprint.h.
|
protected |
Definition at line 60 of file footprint.h.
|
protected |
Definition at line 55 of file footprint.h.
|
protected |
Definition at line 58 of file footprint.h.
|
protected |
Definition at line 54 of file footprint.h.
|
protected |
Definition at line 56 of file footprint.h.
|
protected |
Definition at line 57 of file footprint.h.
|
protected |
Definition at line 61 of file footprint.h.