16 #ifndef NAV2_CORE__WAYPOINT_TASK_EXECUTOR_HPP_
17 #define NAV2_CORE__WAYPOINT_TASK_EXECUTOR_HPP_
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
53 const nav2::LifecycleNode::WeakPtr & parent,
54 const std::string & plugin_name) = 0;
65 const geometry_msgs::msg::PoseStamped & curr_pose,
const int & curr_waypoint_index) = 0;
Base class for creating a plugin in order to perform a specific task at waypoint arrivals.
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.
WaypointTaskExecutor()
Construct a new Simple Task Execution At Waypoint Base object.
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 t...
virtual ~WaypointTaskExecutor()
Destroy the Simple Task Execution At Waypoint Base object.