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

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

#include <layered_costmap.h>

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. More...
 
Costmap2DgetCostmap ()
 
const std::vector< geometry_msgs::Point > & getFootprint ()
 Returns the latest footprint stored with setFootprint(). More...
 
const std::string & getGlobalFrameID () const noexcept
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
 ~LayeredCostmap ()
 Destructor. More...
 

Private Attributes

unsigned int bx0_
 
unsigned int bxn_
 
unsigned int by0_
 
unsigned int byn_
 
double circumscribed_radius_
 
Costmap2D costmap_
 
bool current_
 < More...
 
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 91 of file layered_costmap.h.

Constructor & Destructor Documentation

◆ LayeredCostmap()

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.

◆ ~LayeredCostmap()

costmap_2d::LayeredCostmap::~LayeredCostmap ( )

Destructor.

Definition at line 74 of file layered_costmap.cpp.

Member Function Documentation

◆ addPlugin()

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

Definition at line 148 of file layered_costmap.h.

◆ getBounds()

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

Definition at line 158 of file layered_costmap.h.

◆ getCircumscribedRadius()

double costmap_2d::LayeredCostmap::getCircumscribedRadius ( )
inline

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 184 of file layered_costmap.h.

◆ getCostmap()

Costmap2D* costmap_2d::LayeredCostmap::getCostmap ( )
inline

Definition at line 128 of file layered_costmap.h.

◆ getFootprint()

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

Returns the latest footprint stored with setFootprint().

Definition at line 177 of file layered_costmap.h.

◆ getGlobalFrameID()

const std::string& costmap_2d::LayeredCostmap::getGlobalFrameID ( ) const
inlinenoexcept

Definition at line 110 of file layered_costmap.h.

◆ getInscribedRadius()

double costmap_2d::LayeredCostmap::getInscribedRadius ( )
inline

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 191 of file layered_costmap.h.

◆ getPlugins()

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

Definition at line 143 of file layered_costmap.h.

◆ getUpdatedBounds()

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

Definition at line 118 of file layered_costmap.h.

◆ isCurrent()

bool costmap_2d::LayeredCostmap::isCurrent ( )

Definition at line 165 of file layered_costmap.cpp.

◆ isInitialized()

bool costmap_2d::LayeredCostmap::isInitialized ( )
inline

Definition at line 166 of file layered_costmap.h.

◆ isRolling()

bool costmap_2d::LayeredCostmap::isRolling ( )
inline

Definition at line 133 of file layered_costmap.h.

◆ isSizeLocked()

bool costmap_2d::LayeredCostmap::isSizeLocked ( )
inline

Definition at line 153 of file layered_costmap.h.

◆ isTrackingUnknown()

bool costmap_2d::LayeredCostmap::isTrackingUnknown ( )
inline

Definition at line 138 of file layered_costmap.h.

◆ resizeMap()

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.

◆ setFootprint()

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 177 of file layered_costmap.cpp.

◆ updateMap()

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

◆ bx0_

unsigned int costmap_2d::LayeredCostmap::bx0_
private

Definition at line 201 of file layered_costmap.h.

◆ bxn_

unsigned int costmap_2d::LayeredCostmap::bxn_
private

Definition at line 201 of file layered_costmap.h.

◆ by0_

unsigned int costmap_2d::LayeredCostmap::by0_
private

Definition at line 201 of file layered_costmap.h.

◆ byn_

unsigned int costmap_2d::LayeredCostmap::byn_
private

Definition at line 201 of file layered_costmap.h.

◆ circumscribed_radius_

double costmap_2d::LayeredCostmap::circumscribed_radius_
private

Definition at line 207 of file layered_costmap.h.

◆ costmap_

Costmap2D costmap_2d::LayeredCostmap::costmap_
private

Definition at line 194 of file layered_costmap.h.

◆ current_

bool costmap_2d::LayeredCostmap::current_
private

<

Whether or not the costmap should roll with the robot

Definition at line 199 of file layered_costmap.h.

◆ footprint_

std::vector<geometry_msgs::Point> costmap_2d::LayeredCostmap::footprint_
private

Definition at line 208 of file layered_costmap.h.

◆ global_frame_

std::string costmap_2d::LayeredCostmap::global_frame_
private

Definition at line 195 of file layered_costmap.h.

◆ initialized_

bool costmap_2d::LayeredCostmap::initialized_
private

Definition at line 205 of file layered_costmap.h.

◆ inscribed_radius_

double costmap_2d::LayeredCostmap::inscribed_radius_
private

Definition at line 207 of file layered_costmap.h.

◆ maxx_

double costmap_2d::LayeredCostmap::maxx_
private

Definition at line 200 of file layered_costmap.h.

◆ maxy_

double costmap_2d::LayeredCostmap::maxy_
private

Definition at line 200 of file layered_costmap.h.

◆ minx_

double costmap_2d::LayeredCostmap::minx_
private

Definition at line 200 of file layered_costmap.h.

◆ miny_

double costmap_2d::LayeredCostmap::miny_
private

Definition at line 200 of file layered_costmap.h.

◆ plugins_

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

Definition at line 203 of file layered_costmap.h.

◆ rolling_window_

bool costmap_2d::LayeredCostmap::rolling_window_
private

Definition at line 197 of file layered_costmap.h.

◆ size_locked_

bool costmap_2d::LayeredCostmap::size_locked_
private

Definition at line 206 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 Mon Mar 6 2023 03:50:17