Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_costmap_2d::FootprintSubscriber Class Reference

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>

Collaboration diagram for nav2_costmap_2d::FootprintSubscriber:
Collaboration graph
[legend]

Public Member Functions

template<typename NodeT >
 FootprintSubscriber (const NodeT &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.
 

Protected Attributes

tf2_ros::Buffer & tf_
 
std::string robot_base_frame_
 
double transform_tolerance_
 
bool footprint_received_ {false}
 
geometry_msgs::msg::PolygonStamped::SharedPtr footprint_
 
nav2::Subscription< geometry_msgs::msg::PolygonStamped >::SharedPtr footprint_sub_
 

Detailed Description

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.

Member Function Documentation

◆ getFootprintInRobotFrame()

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).

Parameters
footprintOutput param. Latest received footprint, unoriented
footprint_headerOutput param. Header associated with the footprint
Returns
False if no footprint has been received or if transformation failed

Definition at line 45 of file footprint_subscriber.cpp.

References getFootprintRaw(), and nav2_costmap_2d::transformFootprint().

Referenced by nav2_costmap_2d::CostmapTopicCollisionChecker::getFootprint().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getFootprintRaw()

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).

Parameters
footprintOutput param. Latest received footprint
footprint_headerOutput param. Header associated with the footprint
Returns
False if no footprint has been received

Definition at line 29 of file footprint_subscriber.cpp.

References nav2_costmap_2d::toPointVector().

Referenced by getFootprintInRobotFrame().

Here is the call graph for this function:
Here is the caller graph for this function:

The documentation for this class was generated from the following files: