Class InputAtWaypoint

Inheritance Relationships

Base Type

  • public nav2_core::WaypointTaskExecutor

Class Documentation

class InputAtWaypoint : public nav2_core::WaypointTaskExecutor

Simple plugin based on WaypointTaskExecutor, lets robot to wait for a user input at waypoint arrival.

Public Functions

InputAtWaypoint()

Construct a new Input At Waypoint Arrival object.

~InputAtWaypoint()

Destroy the Input At Waypoint Arrival object.

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

declares and loads parameters used

Parameters:
  • parent – parent node

  • plugin_name – name of plugin

virtual bool processAtWaypoint(const geometry_msgs::msg::PoseStamped &curr_pose, const int &curr_waypoint_index)

Processor.

Parameters:
  • curr_pose – current pose of the robot

  • curr_waypoint_index – current waypoint, that robot just arrived

Returns:

if task execution failed

Protected Functions

void Cb(const std_msgs::msg::Empty::SharedPtr msg)

Processor callback.

Parameters:

msg – Empty message

Protected Attributes

bool input_received_
bool is_enabled_
rclcpp::Duration timeout_
rclcpp::Logger logger_ = {rclcpp::get_logger("nav2_waypoint_follower")}
rclcpp::Clock::SharedPtr clock_
std::mutex mutex_
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr subscription_