|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Subscriber to the footprint topic to get current robot footprint (if changing) for use in collision avoidance. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp>

Public Member Functions | |
| FootprintSubscriber (const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name, tf2_ros::Buffer &tf, std::string robot_base_frame="base_link", double transform_tolerance=0.1) | |
| A constructor. | |
| FootprintSubscriber (const rclcpp::Node::WeakPtr &parent, const std::string &topic_name, tf2_ros::Buffer &tf, std::string robot_base_frame="base_link", double transform_tolerance=0.1) | |
| A constructor. | |
| ~FootprintSubscriber () | |
| A destructor. | |
| bool | getFootprintRaw (std::vector< geometry_msgs::msg::Point > &footprint, std_msgs::msg::Header &footprint_header) |
| Returns the latest robot footprint, in the form as received from topic (oriented). More... | |
| bool | getFootprintInRobotFrame (std::vector< geometry_msgs::msg::Point > &footprint, std_msgs::msg::Header &footprint_header) |
| Returns the latest robot footprint, transformed into robot base frame (unoriented). More... | |
Protected Member Functions | |
| void | footprint_callback (const geometry_msgs::msg::PolygonStamped::SharedPtr msg) |
| Callback to process new footprint updates. | |
Subscriber to the footprint topic to get current robot footprint (if changing) for use in collision avoidance.
Definition at line 33 of file footprint_subscriber.hpp.
| bool nav2_costmap_2d::FootprintSubscriber::getFootprintInRobotFrame | ( | std::vector< geometry_msgs::msg::Point > & | footprint, |
| std_msgs::msg::Header & | footprint_header | ||
| ) |
Returns the latest robot footprint, transformed into robot base frame (unoriented).
| footprint | Output param. Latest received footprint, unoriented |
| footprint_header | Output param. Header associated with the footprint |
Definition at line 78 of file footprint_subscriber.cpp.
References getFootprintRaw(), and nav2_costmap_2d::transformFootprint().
Referenced by nav2_costmap_2d::CostmapTopicCollisionChecker::getFootprint().


| bool nav2_costmap_2d::FootprintSubscriber::getFootprintRaw | ( | std::vector< geometry_msgs::msg::Point > & | footprint, |
| std_msgs::msg::Header & | footprint_header | ||
| ) |
Returns the latest robot footprint, in the form as received from topic (oriented).
| footprint | Output param. Latest received footprint |
| footprint_header | Output param. Header associated with the footprint |
Definition at line 61 of file footprint_subscriber.cpp.
References nav2_costmap_2d::toPointVector().
Referenced by getFootprintInRobotFrame().

