|
Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Simple plugin based on WaypointTaskExecutor, lets 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>


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_ |
Simple plugin based on WaypointTaskExecutor, lets 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.
|
virtual |
declares and loads parameters used (waypoint_pause_duration_)
| parent | parent node that plugin will be created withing(waypoint_follower in this case) |
| plugin_name |
Implements nav2_core::WaypointTaskExecutor.
Definition at line 36 of file wait_at_waypoint.cpp.
|
virtual |
Override this to define the body of your task that you would like to execute once the robot arrived to waypoint.
| curr_pose | current pose of the robot |
| curr_waypoint_index | current waypoint, that robot just arrived |
Implements nav2_core::WaypointTaskExecutor.
Definition at line 71 of file wait_at_waypoint.cpp.