Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_waypoint_follower::InputAtWaypoint Class Reference

Simple plugin based on WaypointTaskExecutor, lets robot to wait for a user input at waypoint arrival. More...

#include <nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/input_at_waypoint.hpp>

Inheritance diagram for nav2_waypoint_follower::InputAtWaypoint:
Inheritance graph
[legend]
Collaboration diagram for nav2_waypoint_follower::InputAtWaypoint:
Collaboration graph
[legend]

Public Member Functions

 InputAtWaypoint ()
 Construct a new Input At Waypoint Arrival object.
 
 ~InputAtWaypoint ()
 Destroy the Input At Waypoint Arrival object.
 
void initialize (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name)
 declares and loads parameters used More...
 
bool processAtWaypoint (const geometry_msgs::msg::PoseStamped &curr_pose, const int &curr_waypoint_index)
 Processor. More...
 
- Public Member Functions inherited from nav2_core::WaypointTaskExecutor
 WaypointTaskExecutor ()
 Construct a new Simple Task Execution At Waypoint Base object.
 
virtual ~WaypointTaskExecutor ()
 Destroy the Simple Task Execution At Waypoint Base object.
 

Protected Member Functions

void Cb (const std_msgs::msg::Empty::SharedPtr msg)
 Processor callback. More...
 

Protected Attributes

bool input_received_
 
bool is_enabled_
 
rclcpp::Duration timeout_
 
rclcpp::Logger logger_ {rclcpp::get_logger("nav2_waypoint_follower")}
 
rclcpp::Clock::SharedPtr clock_
 
std::mutex mutex_
 
rclcpp::Subscription< std_msgs::msg::Empty >::SharedPtr subscription_
 

Detailed Description

Simple plugin based on WaypointTaskExecutor, lets robot to wait for a user input at waypoint arrival.

Definition at line 34 of file input_at_waypoint.hpp.

Member Function Documentation

◆ Cb()

void nav2_waypoint_follower::InputAtWaypoint::Cb ( const std_msgs::msg::Empty::SharedPtr  msg)
protected

Processor callback.

Parameters
msgEmpty message

Definition at line 75 of file input_at_waypoint.cpp.

Referenced by initialize().

Here is the caller graph for this function:

◆ initialize()

void nav2_waypoint_follower::InputAtWaypoint::initialize ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
const std::string &  plugin_name 
)
virtual

declares and loads parameters used

Parameters
parentparent node
plugin_namename of plugin

Implements nav2_core::WaypointTaskExecutor.

Definition at line 39 of file input_at_waypoint.cpp.

References Cb().

Here is the call graph for this function:

◆ processAtWaypoint()

bool nav2_waypoint_follower::InputAtWaypoint::processAtWaypoint ( const geometry_msgs::msg::PoseStamped &  curr_pose,
const int &  curr_waypoint_index 
)
virtual

Processor.

Parameters
curr_posecurrent pose of the robot
curr_waypoint_indexcurrent waypoint, that robot just arrived
Returns
if task execution failed

Implements nav2_core::WaypointTaskExecutor.

Definition at line 81 of file input_at_waypoint.cpp.


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