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

A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacles in either the form of PointCloud or LaserScan messages. More...

#include <costmap_2d_ros.h>

Public Member Functions

 Costmap2DROS (const std::string &name, tf2_ros::Buffer &tf)
 Constructor for the wrapper. More...
 
const std::string & getBaseFrameID () const noexcept
 Returns the local frame of the costmap. More...
 
Costmap2DgetCostmap () const
 Return a pointer to the "master" costmap which receives updates from all the layers. More...
 
const std::string & getGlobalFrameID () const noexcept
 Returns the global frame of the costmap. More...
 
LayeredCostmapgetLayeredCostmap () const
 
const std::string & getName () const noexcept
 Returns costmap name. More...
 
void getOrientedFootprint (std::vector< geometry_msgs::Point > &oriented_footprint) const
 Build the oriented footprint of the robot at the robot's current pose. More...
 
const std::vector< geometry_msgs::Point > & getRobotFootprint () const noexcept
 Return the current footprint of the robot as a vector of points. More...
 
geometry_msgs::Polygon getRobotFootprintPolygon () const
 Returns the current padded footprint as a geometry_msgs::Polygon. More...
 
bool getRobotPose (geometry_msgs::PoseStamped &global_pose) const
 Get the pose of the robot in the global frame of the costmap. More...
 
double getTransformTolerance () const
 Returns the delay in transform (tf) data that is tolerable in seconds. More...
 
const std::vector< geometry_msgs::Point > & getUnpaddedRobotFootprint () const noexcept
 Return the current unpadded footprint of the robot as a vector of points. More...
 
bool isCurrent () const
 Same as getLayeredCostmap()->isCurrent(). More...
 
bool isStopped () const
 Is the costmap stopped. More...
 
void pause ()
 Stops the costmap from updating, but sensor data still comes in over the wire. More...
 
void resetLayers ()
 Reset each individual layer. More...
 
void resume ()
 Resumes costmap updates. More...
 
void setUnpaddedRobotFootprint (const std::vector< geometry_msgs::Point > &points)
 Set the footprint of the robot to be the given set of points, padded by footprint_padding. More...
 
void setUnpaddedRobotFootprintPolygon (const geometry_msgs::Polygon &footprint)
 Set the footprint of the robot to be the given polygon, padded by footprint_padding. More...
 
void start ()
 Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the costmap after calls to either stop() or pause() More...
 
void stop ()
 Stops costmap updates and unsubscribes from sensor topics. More...
 
void updateMap ()
 
 ~Costmap2DROS ()
 

Protected Attributes

std::string global_frame_
 The global frame for the costmap. More...
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
std::string robot_base_frame_
 The frame_id of the robot base. More...
 
tf2_ros::Buffertf_
 Used for transforming point clouds. More...
 
double transform_tolerance_
 timeout before transform errors More...
 

Private Member Functions

void checkOldParam (ros::NodeHandle &nh, const std::string &param_name)
 
void copyParentParameters (const std::string &plugin_name, const std::string &plugin_type, ros::NodeHandle &nh)
 
void loadOldParameters (ros::NodeHandle &nh)
 
void mapUpdateLoop (double frequency)
 
void movementCB (const ros::TimerEvent &event)
 
void readFootprintFromConfig (const costmap_2d::Costmap2DConfig &new_config, const costmap_2d::Costmap2DConfig &old_config)
 Set the footprint from the new_config object. More...
 
void reconfigureCB (costmap_2d::Costmap2DConfig &config, uint32_t level)
 
void warnForOldParameters (ros::NodeHandle &nh)
 

Private Attributes

boost::recursive_mutex configuration_mutex_
 
dynamic_reconfigure::Server< costmap_2d::Costmap2DConfig > * dsrv_
 
float footprint_padding_
 
ros::Publisher footprint_pub_
 
ros::Subscriber footprint_sub_
 
bool initialized_
 
ros::Time last_publish_
 
boost::thread * map_update_thread_
 A thread for updating the map. More...
 
bool map_update_thread_shutdown_
 
costmap_2d::Costmap2DConfig old_config_
 
std::vector< geometry_msgs::Pointpadded_footprint_
 
pluginlib::ClassLoader< Layerplugin_loader_
 
ros::Duration publish_cycle
 
Costmap2DPublisherpublisher_
 
bool stop_updates_
 
bool stopped_
 
std::vector< geometry_msgs::Pointunpadded_footprint_
 

Detailed Description

A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacles in either the form of PointCloud or LaserScan messages.

Definition at line 74 of file costmap_2d_ros.h.

Constructor & Destructor Documentation

◆ Costmap2DROS()

costmap_2d::Costmap2DROS::Costmap2DROS ( const std::string &  name,
tf2_ros::Buffer tf 
)

Constructor for the wrapper.

Parameters
nameThe name for this costmap
tfA reference to a TransformListener

Definition at line 64 of file costmap_2d_ros.cpp.

◆ ~Costmap2DROS()

costmap_2d::Costmap2DROS::~Costmap2DROS ( )

Definition at line 177 of file costmap_2d_ros.cpp.

Member Function Documentation

◆ checkOldParam()

void costmap_2d::Costmap2DROS::checkOldParam ( ros::NodeHandle nh,
const std::string &  param_name 
)
private

Definition at line 305 of file costmap_2d_ros.cpp.

◆ copyParentParameters()

void costmap_2d::Costmap2DROS::copyParentParameters ( const std::string &  plugin_name,
const std::string &  plugin_type,
ros::NodeHandle nh 
)
private

Definition at line 265 of file costmap_2d_ros.cpp.

◆ getBaseFrameID()

const std::string& costmap_2d::Costmap2DROS::getBaseFrameID ( ) const
inlinenoexcept

Returns the local frame of the costmap.

Returns
The local frame of the costmap

Definition at line 168 of file costmap_2d_ros.h.

◆ getCostmap()

Costmap2D* costmap_2d::Costmap2DROS::getCostmap ( ) const
inline

Return a pointer to the "master" costmap which receives updates from all the layers.

Same as calling getLayeredCostmap()->getCostmap().

Definition at line 150 of file costmap_2d_ros.h.

◆ getGlobalFrameID()

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

Returns the global frame of the costmap.

Returns
The global frame of the costmap

Definition at line 159 of file costmap_2d_ros.h.

◆ getLayeredCostmap()

LayeredCostmap* costmap_2d::Costmap2DROS::getLayeredCostmap ( ) const
inline

Definition at line 172 of file costmap_2d_ros.h.

◆ getName()

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

Returns costmap name.

Definition at line 136 of file costmap_2d_ros.h.

◆ getOrientedFootprint()

void costmap_2d::Costmap2DROS::getOrientedFootprint ( std::vector< geometry_msgs::Point > &  oriented_footprint) const

Build the oriented footprint of the robot at the robot's current pose.

Parameters
oriented_footprintWill be filled with the points in the oriented footprint of the robot

Definition at line 597 of file costmap_2d_ros.cpp.

◆ getRobotFootprint()

const std::vector<geometry_msgs::Point>& costmap_2d::Costmap2DROS::getRobotFootprint ( ) const
inlinenoexcept

Return the current footprint of the robot as a vector of points.

This version of the footprint is padded by the footprint_padding_ distance, set in the rosparam "footprint_padding".

The footprint initially comes from the rosparam "footprint" but can be overwritten by dynamic reconfigure or by messages received on the "footprint" topic.

Definition at line 191 of file costmap_2d_ros.h.

◆ getRobotFootprintPolygon()

geometry_msgs::Polygon costmap_2d::Costmap2DROS::getRobotFootprintPolygon ( ) const
inline

Returns the current padded footprint as a geometry_msgs::Polygon.

Definition at line 178 of file costmap_2d_ros.h.

◆ getRobotPose()

bool costmap_2d::Costmap2DROS::getRobotPose ( geometry_msgs::PoseStamped &  global_pose) const

Get the pose of the robot in the global frame of the costmap.

Parameters
global_poseWill be set to the pose of the robot in the global frame of the costmap
Returns
True if the pose was set successfully, false otherwise

Definition at line 546 of file costmap_2d_ros.cpp.

◆ getTransformTolerance()

double costmap_2d::Costmap2DROS::getTransformTolerance ( ) const
inline

Returns the delay in transform (tf) data that is tolerable in seconds.

Definition at line 142 of file costmap_2d_ros.h.

◆ getUnpaddedRobotFootprint()

const std::vector<geometry_msgs::Point>& costmap_2d::Costmap2DROS::getUnpaddedRobotFootprint ( ) const
inlinenoexcept

Return the current unpadded footprint of the robot as a vector of points.

This is the raw version of the footprint without padding.

The footprint initially comes from the rosparam "footprint" but can be overwritten by dynamic reconfigure or by messages received on the "footprint" topic.

Definition at line 203 of file costmap_2d_ros.h.

◆ isCurrent()

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

Same as getLayeredCostmap()->isCurrent().

Definition at line 115 of file costmap_2d_ros.h.

◆ isStopped()

bool costmap_2d::Costmap2DROS::isStopped ( ) const
inline

Is the costmap stopped.

Definition at line 123 of file costmap_2d_ros.h.

◆ loadOldParameters()

void costmap_2d::Costmap2DROS::loadOldParameters ( ros::NodeHandle nh)
private

Definition at line 192 of file costmap_2d_ros.cpp.

◆ mapUpdateLoop()

void costmap_2d::Costmap2DROS::mapUpdateLoop ( double  frequency)
private

Definition at line 412 of file costmap_2d_ros.cpp.

◆ movementCB()

void costmap_2d::Costmap2DROS::movementCB ( const ros::TimerEvent event)
private

Definition at line 399 of file costmap_2d_ros.cpp.

◆ pause()

void costmap_2d::Costmap2DROS::pause ( )

Stops the costmap from updating, but sensor data still comes in over the wire.

Definition at line 517 of file costmap_2d_ros.cpp.

◆ readFootprintFromConfig()

void costmap_2d::Costmap2DROS::readFootprintFromConfig ( const costmap_2d::Costmap2DConfig &  new_config,
const costmap_2d::Costmap2DConfig &  old_config 
)
private

Set the footprint from the new_config object.

If the values of footprint and robot_radius are the same in new_config and old_config, nothing is changed.

Definition at line 358 of file costmap_2d_ros.cpp.

◆ reconfigureCB()

void costmap_2d::Costmap2DROS::reconfigureCB ( costmap_2d::Costmap2DConfig &  config,
uint32_t  level 
)
private

Definition at line 311 of file costmap_2d_ros.cpp.

◆ resetLayers()

void costmap_2d::Costmap2DROS::resetLayers ( )

Reset each individual layer.

Definition at line 534 of file costmap_2d_ros.cpp.

◆ resume()

void costmap_2d::Costmap2DROS::resume ( )

Resumes costmap updates.

Definition at line 523 of file costmap_2d_ros.cpp.

◆ setUnpaddedRobotFootprint()

void costmap_2d::Costmap2DROS::setUnpaddedRobotFootprint ( const std::vector< geometry_msgs::Point > &  points)

Set the footprint of the robot to be the given set of points, padded by footprint_padding.

Should be a convex polygon, though this is not enforced.

First expands the given polygon by footprint_padding_ and then sets padded_footprint_ and calls layered_costmap_->setFootprint(). Also saves the unpadded footprint, which is available from getUnpaddedRobotFootprint().

Definition at line 390 of file costmap_2d_ros.cpp.

◆ setUnpaddedRobotFootprintPolygon()

void costmap_2d::Costmap2DROS::setUnpaddedRobotFootprintPolygon ( const geometry_msgs::Polygon &  footprint)

Set the footprint of the robot to be the given polygon, padded by footprint_padding.

Should be a convex polygon, though this is not enforced.

First expands the given polygon by footprint_padding_ and then sets padded_footprint_ and calls layered_costmap_->setFootprint(). Also saves the unpadded footprint, which is available from getUnpaddedRobotFootprint().

Definition at line 172 of file costmap_2d_ros.cpp.

◆ start()

void costmap_2d::Costmap2DROS::start ( )

Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the costmap after calls to either stop() or pause()

Definition at line 480 of file costmap_2d_ros.cpp.

◆ stop()

void costmap_2d::Costmap2DROS::stop ( )

Stops costmap updates and unsubscribes from sensor topics.

Definition at line 503 of file costmap_2d_ros.cpp.

◆ updateMap()

void costmap_2d::Costmap2DROS::updateMap ( )

Definition at line 455 of file costmap_2d_ros.cpp.

◆ warnForOldParameters()

void costmap_2d::Costmap2DROS::warnForOldParameters ( ros::NodeHandle nh)
private

Definition at line 299 of file costmap_2d_ros.cpp.

Member Data Documentation

◆ configuration_mutex_

boost::recursive_mutex costmap_2d::Costmap2DROS::configuration_mutex_
private

Definition at line 270 of file costmap_2d_ros.h.

◆ dsrv_

dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig>* costmap_2d::Costmap2DROS::dsrv_
private

Definition at line 268 of file costmap_2d_ros.h.

◆ footprint_padding_

float costmap_2d::Costmap2DROS::footprint_padding_
private

Definition at line 276 of file costmap_2d_ros.h.

◆ footprint_pub_

ros::Publisher costmap_2d::Costmap2DROS::footprint_pub_
private

Definition at line 273 of file costmap_2d_ros.h.

◆ footprint_sub_

ros::Subscriber costmap_2d::Costmap2DROS::footprint_sub_
private

Definition at line 272 of file costmap_2d_ros.h.

◆ global_frame_

std::string costmap_2d::Costmap2DROS::global_frame_
protected

The global frame for the costmap.

Definition at line 242 of file costmap_2d_ros.h.

◆ initialized_

bool costmap_2d::Costmap2DROS::initialized_
private

Definition at line 262 of file costmap_2d_ros.h.

◆ last_publish_

ros::Time costmap_2d::Costmap2DROS::last_publish_
private

Definition at line 264 of file costmap_2d_ros.h.

◆ layered_costmap_

LayeredCostmap* costmap_2d::Costmap2DROS::layered_costmap_
protected

Definition at line 239 of file costmap_2d_ros.h.

◆ map_update_thread_

boost::thread* costmap_2d::Costmap2DROS::map_update_thread_
private

A thread for updating the map.

Definition at line 263 of file costmap_2d_ros.h.

◆ map_update_thread_shutdown_

bool costmap_2d::Costmap2DROS::map_update_thread_shutdown_
private

Definition at line 261 of file costmap_2d_ros.h.

◆ name_

std::string costmap_2d::Costmap2DROS::name_
protected

Definition at line 240 of file costmap_2d_ros.h.

◆ old_config_

costmap_2d::Costmap2DConfig costmap_2d::Costmap2DROS::old_config_
private

Definition at line 277 of file costmap_2d_ros.h.

◆ padded_footprint_

std::vector<geometry_msgs::Point> costmap_2d::Costmap2DROS::padded_footprint_
private

Definition at line 275 of file costmap_2d_ros.h.

◆ plugin_loader_

pluginlib::ClassLoader<Layer> costmap_2d::Costmap2DROS::plugin_loader_
private

Definition at line 266 of file costmap_2d_ros.h.

◆ publish_cycle

ros::Duration costmap_2d::Costmap2DROS::publish_cycle
private

Definition at line 265 of file costmap_2d_ros.h.

◆ publisher_

Costmap2DPublisher* costmap_2d::Costmap2DROS::publisher_
private

Definition at line 267 of file costmap_2d_ros.h.

◆ robot_base_frame_

std::string costmap_2d::Costmap2DROS::robot_base_frame_
protected

The frame_id of the robot base.

Definition at line 243 of file costmap_2d_ros.h.

◆ stop_updates_

bool costmap_2d::Costmap2DROS::stop_updates_
private

Definition at line 262 of file costmap_2d_ros.h.

◆ stopped_

bool costmap_2d::Costmap2DROS::stopped_
private

Definition at line 262 of file costmap_2d_ros.h.

◆ tf_

tf2_ros::Buffer& costmap_2d::Costmap2DROS::tf_
protected

Used for transforming point clouds.

Definition at line 241 of file costmap_2d_ros.h.

◆ transform_tolerance_

double costmap_2d::Costmap2DROS::transform_tolerance_
protected

timeout before transform errors

Definition at line 244 of file costmap_2d_ros.h.

◆ unpadded_footprint_

std::vector<geometry_msgs::Point> costmap_2d::Costmap2DROS::unpadded_footprint_
private

Definition at line 274 of file costmap_2d_ros.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