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

Simple plugin based on WaypointTaskExecutor, let's robot to sleep for a specified amount of time at waypoint arrival. You can reference this class to define your own task and rewrite the body for it. More...

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

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

Public Member Functions

 WaitAtWaypoint ()
 Construct a new Wait At Waypoint Arrival object.
 
 ~WaitAtWaypoint ()
 Destroy the Wait At Waypoint Arrival object.
 
void initialize (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name)
 declares and loads parameters used (waypoint_pause_duration_) More...
 
bool processAtWaypoint (const geometry_msgs::msg::PoseStamped &curr_pose, const int &curr_waypoint_index)
 Override this to define the body of your task that you would like to execute once the robot arrived to waypoint. 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 Attributes

int waypoint_pause_duration_
 
bool is_enabled_
 
rclcpp::Logger logger_ {rclcpp::get_logger("nav2_waypoint_follower")}
 
rclcpp::Clock::SharedPtr clock_
 

Detailed Description

Simple plugin based on WaypointTaskExecutor, let's robot to sleep for a specified amount of time at waypoint arrival. You can reference this class to define your own task and rewrite the body for it.

Definition at line 34 of file wait_at_waypoint.hpp.

Member Function Documentation

◆ initialize()

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

declares and loads parameters used (waypoint_pause_duration_)

Parameters
parentparent node that plugin will be created within (waypoint_follower in this case)
plugin_name

Implements nav2_core::WaypointTaskExecutor.

Definition at line 36 of file wait_at_waypoint.cpp.

◆ processAtWaypoint()

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

Override this to define the body of your task that you would like to execute once the robot arrived to waypoint.

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

Implements nav2_core::WaypointTaskExecutor.

Definition at line 71 of file wait_at_waypoint.cpp.


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