#include <unknown_handle.h>

Public Types | |
| using | Ptr = std::shared_ptr< Costmap3dLayerUnknownHandle > | 
  Public Types inherited from costmap_cspace::Costmap3dLayerBase | |
| using | Ptr = std::shared_ptr< Costmap3dLayerBase > | 
Public Member Functions | |
| Costmap3dLayerUnknownHandle () | |
| void | loadConfig (XmlRpc::XmlRpcValue config) | 
| 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 | |
| int | getRangeMax () const | 
| 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 | |
| int8_t | unknown_cost_ | 
  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 44 of file unknown_handle.h.
| using costmap_cspace::Costmap3dLayerUnknownHandle::Ptr = std::shared_ptr<Costmap3dLayerUnknownHandle> | 
Definition at line 47 of file unknown_handle.h.
      
  | 
  inline | 
Definition at line 53 of file unknown_handle.h.
      
  | 
  inlineprotectedvirtual | 
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 69 of file unknown_handle.h.
      
  | 
  inlinevirtual | 
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 57 of file unknown_handle.h.
      
  | 
  inlinevirtual | 
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 64 of file unknown_handle.h.
      
  | 
  inlineprotectedvirtual | 
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 73 of file unknown_handle.h.
      
  | 
  inlineprotectedvirtual | 
Implements costmap_cspace::Costmap3dLayerBase.
Definition at line 98 of file unknown_handle.h.
      
  | 
  protected | 
Definition at line 50 of file unknown_handle.h.