Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
input_at_waypoint.hpp
1 // Copyright (c) 2020 Samsung Research America
2 // Licensed under the Apache License, Version 2.0 (the "License");
3 // you may not use this file except in compliance with the License.
4 // You may obtain a copy of the License at
5 //
6 // http://www.apache.org/licenses/LICENSE-2.0
7 //
8 // Unless required by applicable law or agreed to in writing, software
9 // distributed under the License is distributed on an "AS IS" BASIS,
10 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
11 // See the License for the specific language governing permissions and
12 // limitations under the License.
13 
14 #ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__INPUT_AT_WAYPOINT_HPP_
15 #define NAV2_WAYPOINT_FOLLOWER__PLUGINS__INPUT_AT_WAYPOINT_HPP_
16 #pragma once
17 
18 #include <string>
19 #include <mutex>
20 #include <memory>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "std_msgs/msg/empty.hpp"
24 #include "rclcpp_lifecycle/lifecycle_node.hpp"
25 #include "nav2_core/waypoint_task_executor.hpp"
26 
27 namespace nav2_waypoint_follower
28 {
29 
35 {
36 public:
42 
48 
54  void initialize(
55  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
56  const std::string & plugin_name);
57 
64  bool processAtWaypoint(
65  const geometry_msgs::msg::PoseStamped & curr_pose, const int & curr_waypoint_index);
66 
67 protected:
72  void Cb(const std_msgs::msg::Empty::SharedPtr msg);
73 
74  bool input_received_;
75  bool is_enabled_;
76  rclcpp::Duration timeout_;
77  rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")};
78  rclcpp::Clock::SharedPtr clock_;
79  std::mutex mutex_;
80  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr subscription_;
81 };
82 
83 } // namespace nav2_waypoint_follower
84 
85 #endif // NAV2_WAYPOINT_FOLLOWER__PLUGINS__INPUT_AT_WAYPOINT_HPP_
Base class for creating a plugin in order to perform a specific task at waypoint arrivals.
Simple plugin based on WaypointTaskExecutor, lets robot to wait for a user input at waypoint arrival.
InputAtWaypoint()
Construct a new Input At Waypoint Arrival object.
void Cb(const std_msgs::msg::Empty::SharedPtr msg)
Processor callback.
~InputAtWaypoint()
Destroy the Input At Waypoint Arrival object.
void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name)
declares and loads parameters used
bool processAtWaypoint(const geometry_msgs::msg::PoseStamped &curr_pose, const int &curr_waypoint_index)
Processor.