#include <output.h>
Public Types | |
using | Callback = boost::function< bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)> |
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) |
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 | |
costmap_cspace_msgs::CSpace3DUpdate::Ptr | generateUpdateMsg () |
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 | |
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_ |
using costmap_cspace::Costmap3dLayerOutput::Callback = boost::function<bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)> |
using costmap_cspace::Costmap3dLayerOutput::Ptr = std::shared_ptr<Costmap3dLayerOutput> |
|
inlineprotected |
|
inlineprotectedvirtual |
Implements costmap_cspace::Costmap3dLayerBase.
|
inlinevirtual |
Implements costmap_cspace::Costmap3dLayerBase.
|
inline |
|
inlinevirtual |
Implements costmap_cspace::Costmap3dLayerBase.
|
inlineprotectedvirtual |
Implements costmap_cspace::Costmap3dLayerBase.
|
inlineprotectedvirtual |
Implements costmap_cspace::Costmap3dLayerBase.
|
protected |
|
protected |