Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
costmap_cspace::Costmap3dLayerUnknownHandle Class Reference

#include <unknown_handle.h>

Inheritance diagram for costmap_cspace::Costmap3dLayerUnknownHandle:
Inheritance graph
[legend]

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 &region)
 
- Protected Member Functions inherited from costmap_cspace::Costmap3dLayerBase
void setBaseMapChain ()
 
bool updateChainEntry (const UpdatedRegion &region, 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_
 

Detailed Description

Definition at line 42 of file unknown_handle.h.

Member Typedef Documentation

Definition at line 45 of file unknown_handle.h.

Constructor & Destructor Documentation

costmap_cspace::Costmap3dLayerUnknownHandle::Costmap3dLayerUnknownHandle ( )
inline

Definition at line 51 of file unknown_handle.h.

Member Function Documentation

int costmap_cspace::Costmap3dLayerUnknownHandle::getRangeMax ( ) const
inlineprotectedvirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 67 of file unknown_handle.h.

void costmap_cspace::Costmap3dLayerUnknownHandle::loadConfig ( XmlRpc::XmlRpcValue  config)
inlinevirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 55 of file unknown_handle.h.

void costmap_cspace::Costmap3dLayerUnknownHandle::setMapMetaData ( const costmap_cspace_msgs::MapMetaData3D &  info)
inlinevirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 62 of file unknown_handle.h.

bool costmap_cspace::Costmap3dLayerUnknownHandle::updateChain ( const bool  output)
inlineprotectedvirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 71 of file unknown_handle.h.

void costmap_cspace::Costmap3dLayerUnknownHandle::updateCSpace ( const nav_msgs::OccupancyGrid::ConstPtr &  map,
const UpdatedRegion region 
)
inlineprotectedvirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 96 of file unknown_handle.h.

Member Data Documentation

int8_t costmap_cspace::Costmap3dLayerUnknownHandle::unknown_cost_
protected

Definition at line 48 of file unknown_handle.h.


The documentation for this class was generated from the following file:


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:48