Class WaitAtWaypoint

Inheritance Relationships

Base Type

  • public nav2_core::WaypointTaskExecutor

Class Documentation

class WaitAtWaypoint : public nav2_core::WaypointTaskExecutor

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.

Public Functions

WaitAtWaypoint()

Construct a new Wait At Waypoint Arrival object.

~WaitAtWaypoint()

Destroy the Wait At Waypoint Arrival object.

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

declares and loads parameters used (waypoint_pause_duration_)

Parameters:
  • parent – parent node that plugin will be created withing(waypoint_follower in this case)

  • plugin_name

virtual 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.

Parameters:
  • curr_pose – current pose of the robot

  • curr_waypoint_index – current waypoint, that robot just arrived

Returns:

true if task execution was successful

Returns:

false if task execution failed

Protected Attributes

int waypoint_pause_duration_
bool is_enabled_
rclcpp::Logger logger_ = {rclcpp::get_logger("nav2_waypoint_follower")}