15 #ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__WAIT_AT_WAYPOINT_HPP_
16 #define NAV2_WAYPOINT_FOLLOWER__PLUGINS__WAIT_AT_WAYPOINT_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 #include "nav2_core/waypoint_task_executor.hpp"
25 namespace nav2_waypoint_follower
56 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
57 const std::string & plugin_name);
69 const geometry_msgs::msg::PoseStamped & curr_pose,
const int & curr_waypoint_index);
73 int waypoint_pause_duration_;
75 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_waypoint_follower")};
76 rclcpp::Clock::SharedPtr clock_;
Base class for creating a plugin in order to perform a specific task at waypoint arrivals.
Simple plugin based on WaypointTaskExecutor, let's robot to sleep for a specified amount of time at w...
WaitAtWaypoint()
Construct a new 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_)
~WaitAtWaypoint()
Destroy the Wait At Waypoint Arrival object.
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 t...