Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
costmap_2d::Layer Class Reference

#include <layer.h>

Inheritance diagram for costmap_2d::Layer:
Inheritance graph
[legend]

Public Member Functions

virtual void activate ()
 Restart publishers if they've been stopped. More...
 
virtual void deactivate ()
 Stop publishers. More...
 
const std::vector< geometry_msgs::Point > & getFootprint () const
 Convenience function for layered_costmap_->getFootprint(). More...
 
const std::string & getName () const noexcept
 
void initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf)
 
bool isCurrent () const
 Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More...
 
bool isEnabled () const noexcept
 getter if the current layer is enabled. More...
 
 Layer ()
 
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap. More...
 
virtual void onFootprintChanged ()
 LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. More...
 
virtual void reset ()
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds. More...
 
virtual void updateCosts (Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 Actually update the underlying costmap, only within the bounds calculated during UpdateBounds(). More...
 
virtual ~Layer ()
 

Protected Member Functions

virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization. More...
 

Protected Attributes

bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf2_ros::Buffertf_
 

Private Attributes

std::vector< geometry_msgs::Pointfootprint_spec_
 

Detailed Description

Definition at line 84 of file layer.h.

Constructor & Destructor Documentation

◆ Layer()

costmap_2d::Layer::Layer ( )

Definition at line 35 of file layer.cpp.

◆ ~Layer()

virtual costmap_2d::Layer::~Layer ( )
inlinevirtual

Definition at line 116 of file layer.h.

Member Function Documentation

◆ activate()

virtual void costmap_2d::Layer::activate ( )
inlinevirtual

Restart publishers if they've been stopped.

Reimplemented in costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.

Definition at line 112 of file layer.h.

◆ deactivate()

virtual void costmap_2d::Layer::deactivate ( )
inlinevirtual

Stop publishers.

Reimplemented in costmap_2d::ObstacleLayer, and costmap_2d::StaticLayer.

Definition at line 109 of file layer.h.

◆ getFootprint()

const std::vector< geometry_msgs::Point > & costmap_2d::Layer::getFootprint ( ) const

Convenience function for layered_costmap_->getFootprint().

Definition at line 51 of file layer.cpp.

◆ getName()

const std::string& costmap_2d::Layer::getName ( ) const
inlinenoexcept

Definition at line 154 of file layer.h.

◆ initialize()

void costmap_2d::Layer::initialize ( LayeredCostmap parent,
std::string  name,
tf2_ros::Buffer tf 
)

Definition at line 43 of file layer.cpp.

◆ isCurrent()

bool costmap_2d::Layer::isCurrent ( ) const
inline

Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know.

A layer's current state should be managed by the protected variable current_.

Returns
Whether the data in the layer is up to date.

Definition at line 128 of file layer.h.

◆ isEnabled()

bool costmap_2d::Layer::isEnabled ( ) const
inlinenoexcept

getter if the current layer is enabled.

The user may enable/disable a layer though dynamic reconfigure. Disabled layers won't receive calls to

Calls to Layer::activate, Layer::deactivate and Layer::reset won't be blocked.

Definition at line 146 of file layer.h.

◆ matchSize()

virtual void costmap_2d::Layer::matchSize ( )
inlinevirtual

Implement this to make this layer match the size of the parent costmap.

Reimplemented in costmap_2d::VoxelLayer, costmap_2d::StaticLayer, costmap_2d::InflationLayer, and costmap_2d::CostmapLayer.

Definition at line 152 of file layer.h.

◆ onFootprintChanged()

virtual void costmap_2d::Layer::onFootprintChanged ( )
inlinevirtual

LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint.

Reimplemented in costmap_2d::InflationLayer.

Definition at line 165 of file layer.h.

◆ onInitialize()

virtual void costmap_2d::Layer::onInitialize ( )
inlineprotectedvirtual

This is called at the end of initialize(). Override to implement subclass-specific initialization.

tf_, name_, and layered_costmap_ will all be set already when this is called.

Reimplemented in costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, costmap_2d::StaticLayer, and costmap_2d::InflationLayer.

Definition at line 172 of file layer.h.

◆ reset()

virtual void costmap_2d::Layer::reset ( )
inlinevirtual

◆ updateBounds()

virtual void costmap_2d::Layer::updateBounds ( double  robot_x,
double  robot_y,
double  robot_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
inlinevirtual

This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds.

For more details, see "Layered Costmaps for Context-Sensitive Navigation", by Lu et. Al, IROS 2014.

Reimplemented in costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, costmap_2d::StaticLayer, and costmap_2d::InflationLayer.

Definition at line 99 of file layer.h.

◆ updateCosts()

virtual void costmap_2d::Layer::updateCosts ( Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
inlinevirtual

Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().

Reimplemented in costmap_2d::ObstacleLayer, costmap_2d::StaticLayer, and costmap_2d::InflationLayer.

Definition at line 106 of file layer.h.

Member Data Documentation

◆ current_

bool costmap_2d::Layer::current_
protected

Definition at line 175 of file layer.h.

◆ enabled_

bool costmap_2d::Layer::enabled_
protected

Definition at line 176 of file layer.h.

◆ footprint_spec_

std::vector<geometry_msgs::Point> costmap_2d::Layer::footprint_spec_
private

Definition at line 181 of file layer.h.

◆ layered_costmap_

LayeredCostmap* costmap_2d::Layer::layered_costmap_
protected

Definition at line 174 of file layer.h.

◆ name_

std::string costmap_2d::Layer::name_
protected

Definition at line 177 of file layer.h.

◆ tf_

tf2_ros::Buffer* costmap_2d::Layer::tf_
protected

Definition at line 178 of file layer.h.


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


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17