Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
wait_at_waypoint.hpp
1 // Copyright (c) 2020 Fetullah Atas
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__WAIT_AT_WAYPOINT_HPP_
16 #define NAV2_WAYPOINT_FOLLOWER__PLUGINS__WAIT_AT_WAYPOINT_HPP_
17 #pragma once
18 
19 #include <string>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "rclcpp_lifecycle/lifecycle_node.hpp"
23 #include "nav2_core/waypoint_task_executor.hpp"
24 
25 namespace nav2_waypoint_follower
26 {
27 
35 {
36 public:
42 
48 
55  void initialize(
56  const nav2::LifecycleNode::WeakPtr & parent,
57  const std::string & plugin_name);
58 
59 
68  bool processAtWaypoint(
69  const geometry_msgs::msg::PoseStamped & curr_pose, const int & curr_waypoint_index);
70 
71 protected:
72  // the robot will sleep waypoint_pause_duration_ milliseconds
73  int waypoint_pause_duration_;
74  bool is_enabled_;
75  rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")};
76  rclcpp::Clock::SharedPtr clock_;
77 };
78 
79 } // namespace nav2_waypoint_follower
80 #endif // NAV2_WAYPOINT_FOLLOWER__PLUGINS__WAIT_AT_WAYPOINT_HPP_
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 nav2::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...