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>
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.
◆ Costmap2DROS()
costmap_2d::Costmap2DROS::Costmap2DROS |
( |
const std::string & |
name, |
|
|
tf2_ros::Buffer & |
tf |
|
) |
| |
Constructor for the wrapper.
- Parameters
-
name | The name for this costmap |
tf | A reference to a TransformListener |
Definition at line 64 of file costmap_2d_ros.cpp.
◆ ~Costmap2DROS()
costmap_2d::Costmap2DROS::~Costmap2DROS |
( |
| ) |
|
◆ checkOldParam()
void costmap_2d::Costmap2DROS::checkOldParam |
( |
ros::NodeHandle & |
nh, |
|
|
const std::string & |
param_name |
|
) |
| |
|
private |
◆ copyParentParameters()
void costmap_2d::Costmap2DROS::copyParentParameters |
( |
const std::string & |
plugin_name, |
|
|
const std::string & |
plugin_type, |
|
|
ros::NodeHandle & |
nh |
|
) |
| |
|
private |
◆ getBaseFrameID()
std::string costmap_2d::Costmap2DROS::getBaseFrameID |
( |
| ) |
|
|
inline |
Returns the local frame of the costmap.
- Returns
- The local frame of the costmap
Definition at line 160 of file costmap_2d_ros.h.
◆ getCostmap()
Costmap2D* costmap_2d::Costmap2DROS::getCostmap |
( |
| ) |
|
|
inline |
◆ getGlobalFrameID()
std::string costmap_2d::Costmap2DROS::getGlobalFrameID |
( |
| ) |
|
|
inline |
Returns the global frame of the costmap.
- Returns
- The global frame of the costmap
Definition at line 151 of file costmap_2d_ros.h.
◆ getLayeredCostmap()
◆ getName()
std::string costmap_2d::Costmap2DROS::getName |
( |
| ) |
const |
|
inline |
◆ 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_footprint | Will be filled with the points in the oriented footprint of the robot |
Definition at line 624 of file costmap_2d_ros.cpp.
◆ getRobotFootprint()
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 183 of file costmap_2d_ros.h.
◆ getRobotFootprintPolygon()
geometry_msgs::Polygon costmap_2d::Costmap2DROS::getRobotFootprintPolygon |
( |
| ) |
|
|
inline |
Returns the current padded footprint as a geometry_msgs::Polygon.
Definition at line 170 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_pose | Will 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 573 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 134 of file costmap_2d_ros.h.
◆ getUnpaddedRobotFootprint()
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 195 of file costmap_2d_ros.h.
◆ isCurrent()
bool costmap_2d::Costmap2DROS::isCurrent |
( |
| ) |
|
|
inline |
◆ loadOldParameters()
◆ mapUpdateLoop()
void costmap_2d::Costmap2DROS::mapUpdateLoop |
( |
double |
frequency | ) |
|
|
private |
◆ movementCB()
◆ pause()
void costmap_2d::Costmap2DROS::pause |
( |
| ) |
|
Stops the costmap from updating, but sensor data still comes in over the wire.
Definition at line 544 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 365 of file costmap_2d_ros.cpp.
◆ reconfigureCB()
void costmap_2d::Costmap2DROS::reconfigureCB |
( |
costmap_2d::Costmap2DConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
◆ resetLayers()
void costmap_2d::Costmap2DROS::resetLayers |
( |
| ) |
|
◆ resume()
void costmap_2d::Costmap2DROS::resume |
( |
| ) |
|
◆ 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 397 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 180 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 508 of file costmap_2d_ros.cpp.
◆ stop()
void costmap_2d::Costmap2DROS::stop |
( |
| ) |
|
Stops costmap updates and unsubscribes from sensor topics.
Definition at line 530 of file costmap_2d_ros.cpp.
◆ updateMap()
void costmap_2d::Costmap2DROS::updateMap |
( |
| ) |
|
◆ warnForOldParameters()
void costmap_2d::Costmap2DROS::warnForOldParameters |
( |
ros::NodeHandle & |
nh | ) |
|
|
private |
◆ configuration_mutex_
boost::recursive_mutex costmap_2d::Costmap2DROS::configuration_mutex_ |
|
private |
◆ dsrv_
dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig>* costmap_2d::Costmap2DROS::dsrv_ |
|
private |
◆ footprint_padding_
float costmap_2d::Costmap2DROS::footprint_padding_ |
|
private |
◆ footprint_pub_
◆ footprint_sub_
◆ global_frame_
std::string costmap_2d::Costmap2DROS::global_frame_ |
|
protected |
◆ initialized_
bool costmap_2d::Costmap2DROS::initialized_ |
|
private |
◆ last_publish_
ros::Time costmap_2d::Costmap2DROS::last_publish_ |
|
private |
◆ layered_costmap_
◆ map_update_thread_
boost::thread* costmap_2d::Costmap2DROS::map_update_thread_ |
|
private |
◆ map_update_thread_shutdown_
bool costmap_2d::Costmap2DROS::map_update_thread_shutdown_ |
|
private |
◆ name_
std::string costmap_2d::Costmap2DROS::name_ |
|
protected |
◆ old_config_
costmap_2d::Costmap2DConfig costmap_2d::Costmap2DROS::old_config_ |
|
private |
◆ old_pose_
geometry_msgs::PoseStamped costmap_2d::Costmap2DROS::old_pose_ |
|
private |
◆ padded_footprint_
◆ plugin_loader_
◆ publish_cycle
◆ publisher_
◆ robot_base_frame_
std::string costmap_2d::Costmap2DROS::robot_base_frame_ |
|
protected |
◆ robot_stopped_
bool costmap_2d::Costmap2DROS::robot_stopped_ |
|
private |
◆ stop_updates_
bool costmap_2d::Costmap2DROS::stop_updates_ |
|
private |
◆ stopped_
bool costmap_2d::Costmap2DROS::stopped_ |
|
private |
◆ tf_
◆ timer_
◆ transform_tolerance_
double costmap_2d::Costmap2DROS::transform_tolerance_ |
|
protected |
◆ unpadded_footprint_
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 Wed Jun 22 2022 02:07:03