Public Member Functions | Private Attributes
costmap_2d::LayeredCostmap Class Reference

Instantiates different layer plugins and aggregates them into one score. More...

#include <layered_costmap.h>

List of all members.

Public Member Functions

void addPlugin (boost::shared_ptr< Layer > plugin)
void getBounds (unsigned int *x0, unsigned int *xn, unsigned int *y0, unsigned int *yn)
double getCircumscribedRadius ()
 The radius of a circle centered at the origin of the robot which just surrounds all points on the robot's footprint.
Costmap2DgetCostmap ()
const std::vector
< geometry_msgs::Point > & 
getFootprint ()
 Returns the latest footprint stored with setFootprint().
std::string getGlobalFrameID () const
double getInscribedRadius ()
 The radius of a circle centered at the origin of the robot which is just within all points and edges of the robot's footprint.
std::vector< boost::shared_ptr
< Layer > > * 
getPlugins ()
void getUpdatedBounds (double &minx, double &miny, double &maxx, double &maxy)
bool isCurrent ()
bool isInitialized ()
bool isRolling ()
bool isSizeLocked ()
bool isTrackingUnknown ()
 LayeredCostmap (std::string global_frame, bool rolling_window, bool track_unknown)
 Constructor for a costmap.
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
void setFootprint (const std::vector< geometry_msgs::Point > &footprint_spec)
 Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintChanged() in all layers.
void updateMap (double robot_x, double robot_y, double robot_yaw)
 Update the underlying costmap with new data. If you want to update the map outside of the update loop that runs, you can call this.
 ~LayeredCostmap ()
 Destructor.

Private Attributes

unsigned int bx0_
unsigned int bxn_
unsigned int by0_
unsigned int byn_
double circumscribed_radius_
Costmap2D costmap_
bool current_
 <
std::vector< geometry_msgs::Pointfootprint_
std::string global_frame_
bool initialized_
double inscribed_radius_
double maxx_
double maxy_
double minx_
double miny_
std::vector< boost::shared_ptr
< Layer > > 
plugins_
bool rolling_window_
bool size_locked_

Detailed Description

Instantiates different layer plugins and aggregates them into one score.

Definition at line 55 of file layered_costmap.h.


Constructor & Destructor Documentation

costmap_2d::LayeredCostmap::LayeredCostmap ( std::string  global_frame,
bool  rolling_window,
bool  track_unknown 
)

Constructor for a costmap.

Definition at line 50 of file layered_costmap.cpp.

Destructor.

Definition at line 74 of file layered_costmap.cpp.


Member Function Documentation

void costmap_2d::LayeredCostmap::addPlugin ( boost::shared_ptr< Layer plugin) [inline]

Definition at line 112 of file layered_costmap.h.

void costmap_2d::LayeredCostmap::getBounds ( unsigned int *  x0,
unsigned int *  xn,
unsigned int *  y0,
unsigned int *  yn 
) [inline]

Definition at line 122 of file layered_costmap.h.

The radius of a circle centered at the origin of the robot which just surrounds all points on the robot's footprint.

This is updated by setFootprint().

Definition at line 148 of file layered_costmap.h.

Definition at line 92 of file layered_costmap.h.

Returns the latest footprint stored with setFootprint().

Definition at line 141 of file layered_costmap.h.

std::string costmap_2d::LayeredCostmap::getGlobalFrameID ( ) const [inline]

Definition at line 74 of file layered_costmap.h.

The radius of a circle centered at the origin of the robot which is just within all points and edges of the robot's footprint.

This is updated by setFootprint().

Definition at line 155 of file layered_costmap.h.

std::vector<boost::shared_ptr<Layer> >* costmap_2d::LayeredCostmap::getPlugins ( ) [inline]

Definition at line 107 of file layered_costmap.h.

void costmap_2d::LayeredCostmap::getUpdatedBounds ( double &  minx,
double &  miny,
double &  maxx,
double &  maxy 
) [inline]

Definition at line 82 of file layered_costmap.h.

Definition at line 162 of file layered_costmap.cpp.

Definition at line 130 of file layered_costmap.h.

Definition at line 97 of file layered_costmap.h.

Definition at line 117 of file layered_costmap.h.

Definition at line 102 of file layered_costmap.h.

void costmap_2d::LayeredCostmap::resizeMap ( unsigned int  size_x,
unsigned int  size_y,
double  resolution,
double  origin_x,
double  origin_y,
bool  size_locked = false 
)

Definition at line 82 of file layered_costmap.cpp.

void costmap_2d::LayeredCostmap::setFootprint ( const std::vector< geometry_msgs::Point > &  footprint_spec)

Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintChanged() in all layers.

Definition at line 173 of file layered_costmap.cpp.

void costmap_2d::LayeredCostmap::updateMap ( double  robot_x,
double  robot_y,
double  robot_yaw 
)

Update the underlying costmap with new data. If you want to update the map outside of the update loop that runs, you can call this.

Definition at line 95 of file layered_costmap.cpp.


Member Data Documentation

unsigned int costmap_2d::LayeredCostmap::bx0_ [private]

Definition at line 165 of file layered_costmap.h.

unsigned int costmap_2d::LayeredCostmap::bxn_ [private]

Definition at line 165 of file layered_costmap.h.

unsigned int costmap_2d::LayeredCostmap::by0_ [private]

Definition at line 165 of file layered_costmap.h.

unsigned int costmap_2d::LayeredCostmap::byn_ [private]

Definition at line 165 of file layered_costmap.h.

Definition at line 171 of file layered_costmap.h.

Definition at line 158 of file layered_costmap.h.

<

Whether or not the costmap should roll with the robot

Definition at line 163 of file layered_costmap.h.

Definition at line 172 of file layered_costmap.h.

Definition at line 159 of file layered_costmap.h.

Definition at line 169 of file layered_costmap.h.

Definition at line 171 of file layered_costmap.h.

Definition at line 164 of file layered_costmap.h.

Definition at line 164 of file layered_costmap.h.

Definition at line 164 of file layered_costmap.h.

Definition at line 164 of file layered_costmap.h.

std::vector<boost::shared_ptr<Layer> > costmap_2d::LayeredCostmap::plugins_ [private]

Definition at line 167 of file layered_costmap.h.

Definition at line 161 of file layered_costmap.h.

Definition at line 170 of file layered_costmap.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 Sun Mar 3 2019 03:46:15