Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
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 <nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp>
Public Member Functions | |
Costmap2DROS (const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
Constructor for the wrapper. More... | |
Costmap2DROS (const std::string &name) | |
Constructor for the wrapper, the node will be placed in a namespace equal to the node's name. More... | |
Costmap2DROS (const std::string &name, const std::string &parent_namespace, const std::string &local_namespace) | |
Constructor for the wrapper. More... | |
~Costmap2DROS () | |
A destructor. | |
nav2_util::CallbackReturn | on_configure (const rclcpp_lifecycle::State &state) override |
Configure node. | |
nav2_util::CallbackReturn | on_activate (const rclcpp_lifecycle::State &state) override |
Activate node. | |
nav2_util::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &state) override |
Deactivate node. | |
nav2_util::CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &state) override |
Cleanup node. | |
nav2_util::CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &state) override |
shutdown node | |
void | on_rcl_preshutdown () override |
as a child-LifecycleNode : Costmap2DROS may be launched by another Lifecycle Node as a composed module If composed, its parents will handle the shutdown, which includes this module | |
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() | |
void | stop () |
Stops costmap updates and unsubscribes from sensor topics. | |
void | pause () |
Stops the costmap from updating, but sensor data still comes in over the wire. | |
void | resume () |
Resumes costmap updates. | |
void | updateMap () |
Update the map with the layered costmap / plugins. | |
void | resetLayers () |
Reset each individual layer. | |
bool | isCurrent () |
Same as getLayeredCostmap()->isCurrent(). | |
bool | getRobotPose (geometry_msgs::msg::PoseStamped &global_pose) |
Get the pose of the robot in the global frame of the costmap. More... | |
bool | transformPoseToGlobalFrame (const geometry_msgs::msg::PoseStamped &input_pose, geometry_msgs::msg::PoseStamped &transformed_pose) |
Transform the input_pose in the global frame of the costmap. More... | |
std::string | getName () const |
Returns costmap name. | |
double | getTransformTolerance () const |
Returns the delay in transform (tf) data that is tolerable in seconds. | |
Costmap2D * | getCostmap () |
Return a pointer to the "master" costmap which receives updates from all the layers. More... | |
std::string | getGlobalFrameID () |
Returns the global frame of the costmap. More... | |
std::string | getBaseFrameID () |
Returns the local frame of the costmap. More... | |
LayeredCostmap * | getLayeredCostmap () |
Get the layered costmap object used in the node. | |
geometry_msgs::msg::Polygon | getRobotFootprintPolygon () |
Returns the current padded footprint as a geometry_msgs::msg::Polygon. | |
std::vector< geometry_msgs::msg::Point > | getRobotFootprint () |
Return the current footprint of the robot as a vector of points. More... | |
std::vector< geometry_msgs::msg::Point > | getUnpaddedRobotFootprint () |
Return the current unpadded footprint of the robot as a vector of points. More... | |
void | getOrientedFootprint (std::vector< geometry_msgs::msg::Point > &oriented_footprint) |
Build the oriented footprint of the robot at the robot's current pose. More... | |
void | setRobotFootprint (const std::vector< geometry_msgs::msg::Point > &points) |
Set the footprint of the robot to be the given set of points, padded by footprint_padding. More... | |
void | setRobotFootprintPolygon (const geometry_msgs::msg::Polygon::SharedPtr footprint) |
Set the footprint of the robot to be the given polygon, padded by footprint_padding. More... | |
std::shared_ptr< tf2_ros::Buffer > | getTfBuffer () |
bool | getUseRadius () |
Get the costmap's use_radius_ parameter, corresponding to whether the footprint for the robot is a circle with radius robot_radius_ or an arbitrarily defined footprint in footprint_. More... | |
double | getRobotRadius () |
Get the costmap's robot_radius_ parameter, corresponding to raidus of the robot footprint when it is defined as as circle (i.e. when use_radius_ == true). More... | |
![]() | |
LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
A lifecycle node constructor. More... | |
void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
Declare a parameter that has no integer or floating point range constraints. More... | |
void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
Declare a parameter that has a floating point range constraint. More... | |
void | add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false) |
Declare a parameter that has an integer range constraint. More... | |
std::shared_ptr< nav2_util::LifecycleNode > | shared_from_this () |
Get a shared pointer of this. | |
nav2_util::CallbackReturn | on_error (const rclcpp_lifecycle::State &) |
Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More... | |
void | createBond () |
Create bond connection to lifecycle manager. | |
void | destroyBond () |
Destroy bond connection to lifecycle manager. | |
Protected Member Functions | |
void | mapUpdateLoop (double frequency) |
Function on timer for costmap update. | |
void | getParameters () |
Get parameters for node. | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a paramter change is detected. More... | |
![]() | |
void | printLifecycleNodeNotification () |
Print notifications for lifecycle node. | |
void | register_rcl_preshutdown_callback () |
void | runCleanups () |
Protected Attributes | |
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr | footprint_pub_ |
std::unique_ptr< Costmap2DPublisher > | costmap_publisher_ {nullptr} |
rclcpp::Subscription< geometry_msgs::msg::Polygon >::SharedPtr | footprint_sub_ |
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr | parameter_sub_ |
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
rclcpp::executors::SingleThreadedExecutor::SharedPtr | executor_ |
std::unique_ptr< nav2_util::NodeThread > | executor_thread_ |
std::shared_ptr< tf2_ros::Buffer > | tf_buffer_ |
std::shared_ptr< tf2_ros::TransformListener > | tf_listener_ |
std::unique_ptr< LayeredCostmap > | layered_costmap_ {nullptr} |
std::string | name_ |
std::string | parent_namespace_ |
bool | map_update_thread_shutdown_ {false} |
std::atomic< bool > | stop_updates_ {false} |
std::atomic< bool > | initialized_ {false} |
std::atomic< bool > | stopped_ {true} |
std::mutex | _dynamic_parameter_mutex |
std::unique_ptr< std::thread > | map_update_thread_ |
A thread for updating the map. | |
rclcpp::Time | last_publish_ {0, 0, RCL_ROS_TIME} |
rclcpp::Duration | publish_cycle_ {1, 0} |
pluginlib::ClassLoader< Layer > | plugin_loader_ {"nav2_costmap_2d", "nav2_costmap_2d::Layer"} |
bool | always_send_full_costmap_ {false} |
std::string | footprint_ |
float | footprint_padding_ {0} |
std::string | global_frame_ |
The global frame for the costmap. | |
int | map_height_meters_ {0} |
double | map_publish_frequency_ {0} |
double | map_update_frequency_ {0} |
int | map_width_meters_ {0} |
double | origin_x_ {0} |
double | origin_y_ {0} |
std::vector< std::string > | default_plugins_ |
std::vector< std::string > | default_types_ |
std::vector< std::string > | plugin_names_ |
std::vector< std::string > | plugin_types_ |
std::vector< std::string > | filter_names_ |
std::vector< std::string > | filter_types_ |
double | resolution_ {0} |
std::string | robot_base_frame_ |
The frame_id of the robot base. | |
double | robot_radius_ |
bool | rolling_window_ {false} |
Whether to use a rolling window version of the costmap. | |
bool | track_unknown_space_ {false} |
double | transform_tolerance_ {0} |
The timeout before transform errors. | |
bool | is_lifecycle_follower_ {true} |
whether is a child-LifecycleNode or an independent node | |
bool | use_radius_ {false} |
std::vector< geometry_msgs::msg::Point > | unpadded_footprint_ |
std::vector< geometry_msgs::msg::Point > | padded_footprint_ |
std::unique_ptr< ClearCostmapService > | clear_costmap_service_ |
OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler |
![]() | |
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
std::unique_ptr< bond::Bond > | bond_ {nullptr} |
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 73 of file costmap_2d_ros.hpp.
nav2_costmap_2d::Costmap2DROS::Costmap2DROS | ( | const rclcpp::NodeOptions & | options = rclcpp::NodeOptions() | ) |
Constructor for the wrapper.
options | Additional options to control creation of the node. |
Definition at line 64 of file costmap_2d_ros.cpp.
References is_lifecycle_follower_.
|
explicit |
Constructor for the wrapper, the node will be placed in a namespace equal to the node's name.
name | Name of the costmap ROS node |
Definition at line 61 of file costmap_2d_ros.cpp.
|
explicit |
Constructor for the wrapper.
name | Name of the costmap ROS node |
parent_namespace | Absolute namespace of the node hosting the costmap node |
local_namespace | Namespace to append to the parent namespace |
Definition at line 105 of file costmap_2d_ros.cpp.
|
protected |
Callback executed when a paramter change is detected.
parameters | list of changed parameters |
Definition at line 662 of file costmap_2d_ros.cpp.
References global_frame_, nav2_costmap_2d::makeFootprintFromRadius(), nav2_costmap_2d::makeFootprintFromString(), nav2_costmap_2d::padFootprint(), robot_base_frame_, setRobotFootprint(), transform_tolerance_, and updateMap().
Referenced by on_activate().
|
inline |
Returns the local frame of the costmap.
Definition at line 242 of file costmap_2d_ros.hpp.
References robot_base_frame_.
|
inline |
Return a pointer to the "master" costmap which receives updates from all the layers.
Same as calling getLayeredCostmap()->getCostmap().
Definition at line 224 of file costmap_2d_ros.hpp.
Referenced by nav2_costmap_2d::ClearCostmapService::ClearCostmapService(), and nav2_costmap_2d::ClearCostmapService::clearEntirely().
|
inline |
Returns the global frame of the costmap.
Definition at line 233 of file costmap_2d_ros.hpp.
References global_frame_.
void nav2_costmap_2d::Costmap2DROS::getOrientedFootprint | ( | std::vector< geometry_msgs::msg::Point > & | oriented_footprint | ) |
Build the oriented footprint of the robot at the robot's current pose.
oriented_footprint | Will be filled with the points in the oriented footprint of the robot |
Definition at line 442 of file costmap_2d_ros.cpp.
References getRobotPose(), and nav2_costmap_2d::transformFootprint().
|
inline |
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 269 of file costmap_2d_ros.hpp.
bool nav2_costmap_2d::Costmap2DROS::getRobotPose | ( | geometry_msgs::msg::PoseStamped & | global_pose | ) |
Get the pose of the robot in the global frame of the costmap.
global_pose | Will be set to the pose of the robot in the global frame of the costmap |
Definition at line 639 of file costmap_2d_ros.cpp.
References global_frame_, robot_base_frame_, and transform_tolerance_.
Referenced by getOrientedFootprint(), and updateMap().
|
inline |
Get the costmap's robot_radius_ parameter, corresponding to raidus of the robot footprint when it is defined as as circle (i.e. when use_radius_ == true).
Definition at line 332 of file costmap_2d_ros.hpp.
|
inline |
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 281 of file costmap_2d_ros.hpp.
|
inline |
Get the costmap's use_radius_ parameter, corresponding to whether the footprint for the robot is a circle with radius robot_radius_ or an arbitrarily defined footprint in footprint_.
Definition at line 324 of file costmap_2d_ros.hpp.
void nav2_costmap_2d::Costmap2DROS::setRobotFootprint | ( | const std::vector< geometry_msgs::msg::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 426 of file costmap_2d_ros.cpp.
References nav2_costmap_2d::padFootprint().
Referenced by dynamicParametersCallback(), on_configure(), and setRobotFootprintPolygon().
void nav2_costmap_2d::Costmap2DROS::setRobotFootprintPolygon | ( | const geometry_msgs::msg::Polygon::SharedPtr | 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 435 of file costmap_2d_ros.cpp.
References setRobotFootprint(), and nav2_costmap_2d::toPointVector().
Referenced by on_configure().
bool nav2_costmap_2d::Costmap2DROS::transformPoseToGlobalFrame | ( | const geometry_msgs::msg::PoseStamped & | input_pose, |
geometry_msgs::msg::PoseStamped & | transformed_pose | ||
) |
Transform the input_pose in the global frame of the costmap.
input_pose | pose to be transformed |
transformed_pose | pose transformed |
Definition at line 647 of file costmap_2d_ros.cpp.
References global_frame_, and transform_tolerance_.