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

#include <footprint.h>

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

Classes

struct  Rect
 

Public Types

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

Public Member Functions

 Costmap3dLayerFootprint ()
 
PolygongetFootprint ()
 
const geometry_msgs::PolygonStamped & getFootprintMsg () const
 
float getFootprintRadius () const
 
int getRangeMax () const
 
const CSpace3CachegetTemplate () const
 
void loadConfig (XmlRpc::XmlRpcValue config)
 
void setExpansion (const float linear_expand, const float linear_spread, const int linear_spread_min_cost=0)
 
void setFootprint (const Polygon footprint)
 
void setKeepUnknown (const bool keep_unknown)
 
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

void clearTravelableArea (CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg)
 
virtual void generateCSpace (CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg, const UpdatedRegion &region)
 
void generateSpecifiedCSpace (CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid::ConstPtr &msg, const size_t yaw)
 
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

CSpace3Cache cs_template_
 
geometry_msgs::PolygonStamped footprint_
 
Polygon footprint_p_
 
float footprint_radius_
 
bool keep_unknown_
 
float linear_expand_
 
float linear_spread_
 
int linear_spread_min_cost_
 
int range_max_
 
std::vector< bool > unknown_buf_
 
- 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 53 of file footprint.h.

Member Typedef Documentation

◆ Ptr

Definition at line 56 of file footprint.h.

Constructor & Destructor Documentation

◆ Costmap3dLayerFootprint()

costmap_cspace::Costmap3dLayerFootprint::Costmap3dLayerFootprint ( )
inline

Definition at line 76 of file footprint.h.

Member Function Documentation

◆ clearTravelableArea()

void costmap_cspace::Costmap3dLayerFootprint::clearTravelableArea ( CSpace3DMsg::Ptr  map,
const nav_msgs::OccupancyGrid::ConstPtr &  msg 
)
inlineprotected

Definition at line 224 of file footprint.h.

◆ generateCSpace()

virtual void costmap_cspace::Costmap3dLayerFootprint::generateCSpace ( CSpace3DMsg::Ptr  map,
const nav_msgs::OccupancyGrid::ConstPtr &  msg,
const UpdatedRegion region 
)
inlineprotectedvirtual

Definition at line 210 of file footprint.h.

◆ generateSpecifiedCSpace()

void costmap_cspace::Costmap3dLayerFootprint::generateSpecifiedCSpace ( CSpace3DMsg::Ptr  map,
const nav_msgs::OccupancyGrid::ConstPtr &  msg,
const size_t  yaw 
)
inlineprotected

Definition at line 274 of file footprint.h.

◆ getFootprint()

Polygon& costmap_cspace::Costmap3dLayerFootprint::getFootprint ( )
inline

Definition at line 122 of file footprint.h.

◆ getFootprintMsg()

const geometry_msgs::PolygonStamped& costmap_cspace::Costmap3dLayerFootprint::getFootprintMsg ( ) const
inline

Definition at line 126 of file footprint.h.

◆ getFootprintRadius()

float costmap_cspace::Costmap3dLayerFootprint::getFootprintRadius ( ) const
inline

Definition at line 130 of file footprint.h.

◆ getRangeMax()

int costmap_cspace::Costmap3dLayerFootprint::getRangeMax ( ) const
inlinevirtual

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 134 of file footprint.h.

◆ getTemplate()

const CSpace3Cache& costmap_cspace::Costmap3dLayerFootprint::getTemplate ( ) const
inline

Definition at line 138 of file footprint.h.

◆ loadConfig()

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

Implements costmap_cspace::Costmap3dLayerBase.

Reimplemented in costmap_cspace::Costmap3dLayerPlain.

Definition at line 84 of file footprint.h.

◆ setExpansion()

void costmap_cspace::Costmap3dLayerFootprint::setExpansion ( const float  linear_expand,
const float  linear_spread,
const int  linear_spread_min_cost = 0 
)
inline

Definition at line 100 of file footprint.h.

◆ setFootprint()

void costmap_cspace::Costmap3dLayerFootprint::setFootprint ( const Polygon  footprint)
inline

Definition at line 116 of file footprint.h.

◆ setKeepUnknown()

void costmap_cspace::Costmap3dLayerFootprint::setKeepUnknown ( const bool  keep_unknown)
inline

Definition at line 96 of file footprint.h.

◆ setMapMetaData()

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

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 142 of file footprint.h.

◆ updateChain()

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

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 197 of file footprint.h.

◆ updateCSpace()

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

Implements costmap_cspace::Costmap3dLayerBase.

Definition at line 201 of file footprint.h.

Member Data Documentation

◆ cs_template_

CSpace3Cache costmap_cspace::Costmap3dLayerFootprint::cs_template_
protected

Definition at line 67 of file footprint.h.

◆ footprint_

geometry_msgs::PolygonStamped costmap_cspace::Costmap3dLayerFootprint::footprint_
protected

Definition at line 60 of file footprint.h.

◆ footprint_p_

Polygon costmap_cspace::Costmap3dLayerFootprint::footprint_p_
protected

Definition at line 64 of file footprint.h.

◆ footprint_radius_

float costmap_cspace::Costmap3dLayerFootprint::footprint_radius_
protected

Definition at line 59 of file footprint.h.

◆ keep_unknown_

bool costmap_cspace::Costmap3dLayerFootprint::keep_unknown_
protected

Definition at line 65 of file footprint.h.

◆ linear_expand_

float costmap_cspace::Costmap3dLayerFootprint::linear_expand_
protected

Definition at line 61 of file footprint.h.

◆ linear_spread_

float costmap_cspace::Costmap3dLayerFootprint::linear_spread_
protected

Definition at line 62 of file footprint.h.

◆ linear_spread_min_cost_

int costmap_cspace::Costmap3dLayerFootprint::linear_spread_min_cost_
protected

Definition at line 63 of file footprint.h.

◆ range_max_

int costmap_cspace::Costmap3dLayerFootprint::range_max_
protected

Definition at line 72 of file footprint.h.

◆ unknown_buf_

std::vector<bool> costmap_cspace::Costmap3dLayerFootprint::unknown_buf_
protected

Definition at line 73 of file footprint.h.


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


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10