#include <base.h>

Public Member Functions | |
| Costmap3dLayerBase () | |
| int | getAngularGrid () const |
| CSpace3DMsg::Ptr | getMap () |
| CSpace3DMsg::Ptr | getMapOverlay () |
| virtual void | loadConfig (XmlRpc::XmlRpcValue config)=0 |
| 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) |
| virtual void | setMapMetaData (const costmap_cspace_msgs::MapMetaData3D &info)=0 |
| void | setOverlayMode (const MapOverlayMode overlay_mode) |
Protected Member Functions | |
| virtual int | getRangeMax () const =0 |
| void | setBaseMapChain () |
| virtual bool | updateChain (const bool output)=0 |
| bool | updateChainEntry (const UpdatedRegion ®ion, bool output=true) |
| virtual void | updateCSpace (const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion)=0 |
Protected Attributes | |
| 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_ |
| int costmap_cspace::Costmap3dLayerBase::getAngularGrid | ( | ) | const [inline] |
| CSpace3DMsg::Ptr costmap_cspace::Costmap3dLayerBase::getMap | ( | ) | [inline] |
| CSpace3DMsg::Ptr costmap_cspace::Costmap3dLayerBase::getMapOverlay | ( | ) | [inline] |
| virtual int costmap_cspace::Costmap3dLayerBase::getRangeMax | ( | ) | const [protected, pure virtual] |
| virtual void costmap_cspace::Costmap3dLayerBase::loadConfig | ( | XmlRpc::XmlRpcValue | config | ) | [pure virtual] |
| void costmap_cspace::Costmap3dLayerBase::processMapOverlay | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [inline] |
| void costmap_cspace::Costmap3dLayerBase::setAngleResolution | ( | const int | ang_resolution | ) | [inline] |
| void costmap_cspace::Costmap3dLayerBase::setBaseMap | ( | const nav_msgs::OccupancyGrid::ConstPtr & | base_map | ) | [inline] |
| void costmap_cspace::Costmap3dLayerBase::setBaseMapChain | ( | ) | [inline, protected] |
| void costmap_cspace::Costmap3dLayerBase::setChild | ( | Costmap3dLayerBase::Ptr | child | ) | [inline] |
| void costmap_cspace::Costmap3dLayerBase::setMap | ( | CSpace3DMsg::Ptr | map | ) | [inline] |
| virtual void costmap_cspace::Costmap3dLayerBase::setMapMetaData | ( | const costmap_cspace_msgs::MapMetaData3D & | info | ) | [pure virtual] |
| void costmap_cspace::Costmap3dLayerBase::setOverlayMode | ( | const MapOverlayMode | overlay_mode | ) | [inline] |
| virtual bool costmap_cspace::Costmap3dLayerBase::updateChain | ( | const bool | output | ) | [protected, pure virtual] |
| bool costmap_cspace::Costmap3dLayerBase::updateChainEntry | ( | const UpdatedRegion & | region, |
| bool | output = true |
||
| ) | [inline, protected] |
| virtual void costmap_cspace::Costmap3dLayerBase::updateCSpace | ( | const nav_msgs::OccupancyGrid::ConstPtr & | map, |
| const UpdatedRegion & | region | ||
| ) | [protected, pure virtual] |
int costmap_cspace::Costmap3dLayerBase::ang_grid_ [protected] |
Costmap3dLayerBase::Ptr costmap_cspace::Costmap3dLayerBase::child_ [protected] |
CSpace3DMsg::Ptr costmap_cspace::Costmap3dLayerBase::map_ [protected] |
CSpace3DMsg::Ptr costmap_cspace::Costmap3dLayerBase::map_overlay_ [protected] |
nav_msgs::OccupancyGrid::ConstPtr costmap_cspace::Costmap3dLayerBase::map_updated_ [protected] |
Reimplemented in costmap_cspace::Costmap3dLayerOutput.
bool costmap_cspace::Costmap3dLayerBase::root_ [protected] |