#include <output.h>
Public Types | |
using | Ptr = std::shared_ptr< Costmap3dStaticLayerOutput > |
![]() | |
using | Ptr = std::shared_ptr< Costmap3dLayerOutput > |
![]() | |
using | Ptr = std::shared_ptr< Costmap3dLayerBase > |
Protected Member Functions | |
bool | updateChain (const bool output) |
![]() | |
int | getRangeMax () const |
void | updateCSpace (const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion) |
![]() | |
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.