Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
costmap_2d::Layer Class Reference

#include <layer.h>

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

List of all members.

Public Member Functions

virtual void activate ()
 Restart publishers if they've been stopped.
virtual void deactivate ()
 Stop publishers.
const std::vector
< geometry_msgs::Point > & 
getFootprint () const
 Convenience function for layered_costmap_->getFootprint().
std::string getName () const
void initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *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.
 Layer ()
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap.
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.
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.
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().
virtual ~Layer ()

Protected Member Functions

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

Protected Attributes

bool current_
bool enabled_
 Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class.
LayeredCostmaplayered_costmap_
std::string name_
tf::TransformListenertf_

Private Attributes

std::vector< geometry_msgs::Pointfootprint_spec_

Detailed Description

Definition at line 50 of file layer.h.


Constructor & Destructor Documentation

Definition at line 35 of file layer.cpp.

virtual costmap_2d::Layer::~Layer ( ) [inline, virtual]

Definition at line 82 of file layer.h.


Member Function Documentation

virtual void costmap_2d::Layer::activate ( ) [inline, virtual]

Restart publishers if they've been stopped.

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

Definition at line 78 of file layer.h.

virtual void costmap_2d::Layer::deactivate ( ) [inline, virtual]

Stop publishers.

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

Definition at line 75 of file layer.h.

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.

std::string costmap_2d::Layer::getName ( ) const [inline]

Definition at line 102 of file layer.h.

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

Definition at line 43 of file layer.cpp.

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 94 of file layer.h.

virtual void costmap_2d::Layer::matchSize ( ) [inline, virtual]

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

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

Definition at line 100 of file layer.h.

virtual void costmap_2d::Layer::onFootprintChanged ( ) [inline, virtual]

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::ObstacleLayer, and costmap_2d::InflationLayer.

Definition at line 113 of file layer.h.

virtual void costmap_2d::Layer::onInitialize ( ) [inline, protected, virtual]

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::InflationLayer, costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, costmap_2d::StaticLayer, and costmap_2d::FootprintLayer.

Definition at line 120 of file layer.h.

virtual void costmap_2d::Layer::reset ( ) [inline, virtual]
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 
) [inline, virtual]

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::InflationLayer, costmap_2d::VoxelLayer, costmap_2d::ObstacleLayer, costmap_2d::StaticLayer, and costmap_2d::FootprintLayer.

Definition at line 65 of file layer.h.

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

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

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

Definition at line 72 of file layer.h.


Member Data Documentation

bool costmap_2d::Layer::current_ [protected]

Definition at line 123 of file layer.h.

bool costmap_2d::Layer::enabled_ [protected]

Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class.

Definition at line 124 of file layer.h.

Definition at line 129 of file layer.h.

Definition at line 122 of file layer.h.

std::string costmap_2d::Layer::name_ [protected]

Definition at line 125 of file layer.h.

Definition at line 126 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 Thu Aug 27 2015 14:06:55