Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
costmap_cspace::Costmap3dLayerOutput< CALLBACK > Class Template Reference

#include <output.h>

Inheritance diagram for costmap_cspace::Costmap3dLayerOutput< CALLBACK >:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< Costmap3dLayerOutput >
 
- Public Types inherited from costmap_cspace::Costmap3dLayerBase
using Ptr = std::shared_ptr< Costmap3dLayerBase >
 

Public Member Functions

void loadConfig (XmlRpc::XmlRpcValue config)
 
void setHandler (CALLBACK cb)
 
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, const bool update_chain_entry)
 
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
 
void updateCSpace (const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion &region)
 
- Protected Member Functions inherited from costmap_cspace::Costmap3dLayerBase
void setBaseMapChain ()
 
virtual bool updateChain (const bool output)=0
 
bool updateChainEntry (const UpdatedRegion &region, bool output=true)
 

Protected Attributes

CALLBACK cb_
 
UpdatedRegion region_prev_
 
- 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

template<class CALLBACK>
class costmap_cspace::Costmap3dLayerOutput< CALLBACK >

Definition at line 45 of file output.h.

Member Typedef Documentation

◆ Ptr

template<class CALLBACK>
using costmap_cspace::Costmap3dLayerOutput< CALLBACK >::Ptr = std::shared_ptr<Costmap3dLayerOutput>

Definition at line 48 of file output.h.

Member Function Documentation

◆ getRangeMax()

template<class CALLBACK>
int costmap_cspace::Costmap3dLayerOutput< CALLBACK >::getRangeMax ( ) const
inlineprotectedvirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 67 of file output.h.

◆ loadConfig()

template<class CALLBACK>
void costmap_cspace::Costmap3dLayerOutput< CALLBACK >::loadConfig ( XmlRpc::XmlRpcValue  config)
inlinevirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 55 of file output.h.

◆ setHandler()

template<class CALLBACK>
void costmap_cspace::Costmap3dLayerOutput< CALLBACK >::setHandler ( CALLBACK  cb)
inline

Definition at line 58 of file output.h.

◆ setMapMetaData()

template<class CALLBACK>
void costmap_cspace::Costmap3dLayerOutput< CALLBACK >::setMapMetaData ( const costmap_cspace_msgs::MapMetaData3D &  info)
inlinevirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 62 of file output.h.

◆ updateCSpace()

template<class CALLBACK>
void costmap_cspace::Costmap3dLayerOutput< CALLBACK >::updateCSpace ( const nav_msgs::OccupancyGrid::ConstPtr &  map,
const UpdatedRegion region 
)
inlineprotectedvirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 71 of file output.h.

Member Data Documentation

◆ cb_

template<class CALLBACK>
CALLBACK costmap_cspace::Costmap3dLayerOutput< CALLBACK >::cb_
protected

Definition at line 51 of file output.h.

◆ region_prev_

template<class CALLBACK>
UpdatedRegion costmap_cspace::Costmap3dLayerOutput< CALLBACK >::region_prev_
protected

Definition at line 52 of file output.h.


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


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:38:47