#include <output.h>

Public Types | |
| using | Ptr = std::shared_ptr< Costmap3dStaticLayerOutput > |
Public Types inherited from costmap_cspace::Costmap3dLayerOutput< boost::function< bool(const costmap_cspace::CSpace3DMsg::Ptr &)> > | |
| using | Ptr = std::shared_ptr< Costmap3dLayerOutput > |
Public Types inherited from costmap_cspace::Costmap3dLayerBase | |
| using | Ptr = std::shared_ptr< Costmap3dLayerBase > |
Protected Member Functions | |
| bool | updateChain (const bool output) |
Protected Member Functions inherited from costmap_cspace::Costmap3dLayerOutput< boost::function< bool(const costmap_cspace::CSpace3DMsg::Ptr &)> > | |
| int | getRangeMax () const |
| void | updateCSpace (const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion) |
Protected Member Functions inherited from costmap_cspace::Costmap3dLayerBase | |
| virtual int | getRangeMax () const =0 |
| void | setBaseMapChain () |
| bool | updateChainEntry (const UpdatedRegion ®ion, bool output=true) |
| using costmap_cspace::Costmap3dStaticLayerOutput::Ptr = std::shared_ptr<Costmap3dStaticLayerOutput> |
|
inlineprotectedvirtual |
Implements costmap_cspace::Costmap3dLayerBase.