Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | List of all members
nav2_core::WaypointTaskExecutor Class Referenceabstract

Base class for creating a plugin in order to perform a specific task at waypoint arrivals. More...

#include <nav2_core/include/nav2_core/waypoint_task_executor.hpp>

Inheritance diagram for nav2_core::WaypointTaskExecutor:
Inheritance graph
[legend]

Public Member Functions

 WaypointTaskExecutor ()
 Construct a new Simple Task Execution At Waypoint Base object.
 
virtual ~WaypointTaskExecutor ()
 Destroy the Simple Task Execution At Waypoint Base object.
 
virtual void initialize (const nav2::LifecycleNode::WeakPtr &parent, const std::string &plugin_name)=0
 Override this to setup your pub, sub or any ros services that you will use in the plugin. More...
 
virtual bool processAtWaypoint (const geometry_msgs::msg::PoseStamped &curr_pose, const int &curr_waypoint_index)=0
 Override this to define the body of your task that you would like to execute once the robot arrived to waypoint. More...
 

Detailed Description

Base class for creating a plugin in order to perform a specific task at waypoint arrivals.

Definition at line 31 of file waypoint_task_executor.hpp.

Member Function Documentation

◆ initialize()

virtual void nav2_core::WaypointTaskExecutor::initialize ( const nav2::LifecycleNode::WeakPtr &  parent,
const std::string &  plugin_name 
)
pure virtual

Override this to setup your pub, sub or any ros services that you will use in the plugin.

Parameters
parentparent node that plugin will be created within(for an example see nav_waypoint_follower)
plugin_nameplugin name comes from parameters in yaml file

Implemented in nav2_waypoint_follower::WaitAtWaypoint, nav2_waypoint_follower::PhotoAtWaypoint, and nav2_waypoint_follower::InputAtWaypoint.

◆ processAtWaypoint()

virtual bool nav2_core::WaypointTaskExecutor::processAtWaypoint ( const geometry_msgs::msg::PoseStamped &  curr_pose,
const int &  curr_waypoint_index 
)
pure 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

Implemented in nav2_waypoint_follower::WaitAtWaypoint, nav2_waypoint_follower::PhotoAtWaypoint, and nav2_waypoint_follower::InputAtWaypoint.


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