Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
input_at_waypoint.cpp
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 #include "nav2_waypoint_follower/plugins/input_at_waypoint.hpp"
15 
16 #include <string>
17 #include <exception>
18 
19 #include "pluginlib/class_list_macros.hpp"
20 
21 #include "nav2_util/node_utils.hpp"
22 
23 namespace nav2_waypoint_follower
24 {
25 
26 using std::placeholders::_1;
27 
29 : input_received_(false),
30  is_enabled_(true),
31  timeout_(10.0, 0.0)
32 {
33 }
34 
36 {
37 }
38 
40  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
41  const std::string & plugin_name)
42 {
43  auto node = parent.lock();
44 
45  if (!node) {
46  throw std::runtime_error{"Failed to lock node in input at waypoint plugin!"};
47  }
48 
49  logger_ = node->get_logger();
50  clock_ = node->get_clock();
51 
52  double timeout;
53  std::string input_topic;
54  nav2_util::declare_parameter_if_not_declared(
55  node, plugin_name + ".timeout",
56  rclcpp::ParameterValue(10.0));
57  nav2_util::declare_parameter_if_not_declared(
58  node, plugin_name + ".enabled",
59  rclcpp::ParameterValue(true));
60  nav2_util::declare_parameter_if_not_declared(
61  node, plugin_name + ".input_topic",
62  rclcpp::ParameterValue("input_at_waypoint/input"));
63  node->get_parameter(plugin_name + ".timeout", timeout);
64  node->get_parameter(plugin_name + ".enabled", is_enabled_);
65  node->get_parameter(plugin_name + ".input_topic", input_topic);
66 
67  timeout_ = rclcpp::Duration(timeout, 0.0);
68 
69  RCLCPP_INFO(
70  logger_, "InputAtWaypoint: Subscribing to input topic %s.", input_topic.c_str());
71  subscription_ = node->create_subscription<std_msgs::msg::Empty>(
72  input_topic, 1, std::bind(&InputAtWaypoint::Cb, this, _1));
73 }
74 
75 void InputAtWaypoint::Cb(const std_msgs::msg::Empty::SharedPtr /*msg*/)
76 {
77  std::lock_guard<std::mutex> lock(mutex_);
78  input_received_ = true;
79 }
80 
82  const geometry_msgs::msg::PoseStamped & /*curr_pose*/,
83  const int & curr_waypoint_index)
84 {
85  if (!is_enabled_) {
86  return true;
87  }
88 
89  input_received_ = false;
90 
91  rclcpp::Time start = clock_->now();
92  rclcpp::Rate r(50);
93  bool input_received = false;
94  while (clock_->now() - start < timeout_) {
95  {
96  std::lock_guard<std::mutex> lock(mutex_);
97  input_received = input_received_;
98  }
99 
100  if (input_received) {
101  return true;
102  }
103 
104  r.sleep();
105  }
106 
107  RCLCPP_WARN(
108  logger_, "Unable to get external input at wp %i. Moving on.", curr_waypoint_index);
109  return false;
110 }
111 
112 } // namespace nav2_waypoint_follower
113 
114 PLUGINLIB_EXPORT_CLASS(
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.