Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
waypoint_follower.cpp
1 // Copyright (c) 2019 Samsung Research America
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 #include "nav2_waypoint_follower/waypoint_follower.hpp"
16 
17 #include <fstream>
18 #include <memory>
19 #include <streambuf>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
24 namespace nav2_waypoint_follower
25 {
26 
27 using rcl_interfaces::msg::ParameterType;
28 using std::placeholders::_1;
29 
30 WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)
31 : nav2_util::LifecycleNode("waypoint_follower", "", options),
32  waypoint_task_executor_loader_("nav2_waypoint_follower",
33  "nav2_core::WaypointTaskExecutor")
34 {
35  RCLCPP_INFO(get_logger(), "Creating");
36 
37  declare_parameter("stop_on_failure", true);
38  declare_parameter("loop_rate", 20);
39  nav2_util::declare_parameter_if_not_declared(
40  this, std::string("waypoint_task_executor_plugin"),
41  rclcpp::ParameterValue(std::string("wait_at_waypoint")));
42  nav2_util::declare_parameter_if_not_declared(
43  this, std::string("wait_at_waypoint.plugin"),
44  rclcpp::ParameterValue(std::string("nav2_waypoint_follower::WaitAtWaypoint")));
45 }
46 
48 {
49 }
50 
51 nav2_util::CallbackReturn
52 WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/)
53 {
54  RCLCPP_INFO(get_logger(), "Configuring");
55 
56  auto node = shared_from_this();
57 
58  stop_on_failure_ = get_parameter("stop_on_failure").as_bool();
59  loop_rate_ = get_parameter("loop_rate").as_int();
60  waypoint_task_executor_id_ = get_parameter("waypoint_task_executor_plugin").as_string();
61 
62  callback_group_ = create_callback_group(
63  rclcpp::CallbackGroupType::MutuallyExclusive,
64  false);
65  callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface());
66 
67  nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
68  get_node_base_interface(),
69  get_node_graph_interface(),
70  get_node_logging_interface(),
71  get_node_waitables_interface(),
72  "navigate_to_pose", callback_group_);
73 
74  action_server_ = std::make_unique<ActionServer>(
75  get_node_base_interface(),
76  get_node_clock_interface(),
77  get_node_logging_interface(),
78  get_node_waitables_interface(),
79  "follow_waypoints", std::bind(&WaypointFollower::followWaypoints, this));
80 
81  try {
82  waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(
83  this,
84  waypoint_task_executor_id_);
85  waypoint_task_executor_ = waypoint_task_executor_loader_.createUniqueInstance(
86  waypoint_task_executor_type_);
87  RCLCPP_INFO(
88  get_logger(), "Created waypoint_task_executor : %s of type %s",
89  waypoint_task_executor_id_.c_str(), waypoint_task_executor_type_.c_str());
90  waypoint_task_executor_->initialize(node, waypoint_task_executor_id_);
91  } catch (const pluginlib::PluginlibException & ex) {
92  RCLCPP_FATAL(
93  get_logger(),
94  "Failed to create waypoint_task_executor. Exception: %s", ex.what());
95  }
96 
97  return nav2_util::CallbackReturn::SUCCESS;
98 }
99 
100 nav2_util::CallbackReturn
101 WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/)
102 {
103  RCLCPP_INFO(get_logger(), "Activating");
104 
105  action_server_->activate();
106 
107  auto node = shared_from_this();
108  // Add callback for dynamic parameters
109  dyn_params_handler_ = node->add_on_set_parameters_callback(
110  std::bind(&WaypointFollower::dynamicParametersCallback, this, _1));
111 
112  // create bond connection
113  createBond();
114 
115  return nav2_util::CallbackReturn::SUCCESS;
116 }
117 
118 nav2_util::CallbackReturn
119 WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
120 {
121  RCLCPP_INFO(get_logger(), "Deactivating");
122 
123  action_server_->deactivate();
124  dyn_params_handler_.reset();
125 
126  // destroy bond connection
127  destroyBond();
128 
129  return nav2_util::CallbackReturn::SUCCESS;
130 }
131 
132 nav2_util::CallbackReturn
133 WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
134 {
135  RCLCPP_INFO(get_logger(), "Cleaning up");
136 
137  action_server_.reset();
138  nav_to_pose_client_.reset();
139 
140  return nav2_util::CallbackReturn::SUCCESS;
141 }
142 
143 nav2_util::CallbackReturn
144 WaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
145 {
146  RCLCPP_INFO(get_logger(), "Shutting down");
147  return nav2_util::CallbackReturn::SUCCESS;
148 }
149 
150 void
152 {
153  auto goal = action_server_->get_current_goal();
154  auto feedback = std::make_shared<ActionT::Feedback>();
155  auto result = std::make_shared<ActionT::Result>();
156 
157  // Check if request is valid
158  if (!action_server_ || !action_server_->is_server_active()) {
159  RCLCPP_DEBUG(get_logger(), "Action server inactive. Stopping.");
160  return;
161  }
162 
163  RCLCPP_INFO(
164  get_logger(), "Received follow waypoint request with %i waypoints.",
165  static_cast<int>(goal->poses.size()));
166 
167  if (goal->poses.size() == 0) {
168  action_server_->succeeded_current(result);
169  return;
170  }
171 
172  rclcpp::WallRate r(loop_rate_);
173  uint32_t goal_index = 0;
174  bool new_goal = true;
175 
176  while (rclcpp::ok()) {
177  // Check if asked to stop processing action
178  if (action_server_->is_cancel_requested()) {
179  auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
180  callback_group_executor_.spin_until_future_complete(cancel_future);
181  // for result callback processing
182  callback_group_executor_.spin_some();
183  action_server_->terminate_all();
184  return;
185  }
186 
187  // Check if asked to process another action
188  if (action_server_->is_preempt_requested()) {
189  RCLCPP_INFO(get_logger(), "Preempting the goal pose.");
190  goal = action_server_->accept_pending_goal();
191  goal_index = 0;
192  new_goal = true;
193  }
194 
195  // Check if we need to send a new goal
196  if (new_goal) {
197  new_goal = false;
198  ClientT::Goal client_goal;
199  client_goal.pose = goal->poses[goal_index];
200 
201  auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
202  send_goal_options.result_callback =
203  std::bind(&WaypointFollower::resultCallback, this, std::placeholders::_1);
204  send_goal_options.goal_response_callback =
205  std::bind(&WaypointFollower::goalResponseCallback, this, std::placeholders::_1);
206  future_goal_handle_ =
207  nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);
208  current_goal_status_ = ActionStatus::PROCESSING;
209  }
210 
211  feedback->current_waypoint = goal_index;
212  action_server_->publish_feedback(feedback);
213 
214  if (current_goal_status_ == ActionStatus::FAILED) {
215  failed_ids_.push_back(goal_index);
216 
217  if (stop_on_failure_) {
218  RCLCPP_WARN(
219  get_logger(), "Failed to process waypoint %i in waypoint "
220  "list and stop on failure is enabled."
221  " Terminating action.", goal_index);
222  result->missed_waypoints = failed_ids_;
223  action_server_->terminate_current(result);
224  failed_ids_.clear();
225  return;
226  } else {
227  RCLCPP_INFO(
228  get_logger(), "Failed to process waypoint %i,"
229  " moving to next.", goal_index);
230  }
231  } else if (current_goal_status_ == ActionStatus::SUCCEEDED) {
232  RCLCPP_INFO(
233  get_logger(), "Succeeded processing waypoint %i, processing waypoint task execution",
234  goal_index);
235  bool is_task_executed = waypoint_task_executor_->processAtWaypoint(
236  goal->poses[goal_index], goal_index);
237  RCLCPP_INFO(
238  get_logger(), "Task execution at waypoint %i %s", goal_index,
239  is_task_executed ? "succeeded" : "failed!");
240  // if task execution was failed and stop_on_failure_ is on , terminate action
241  if (!is_task_executed && stop_on_failure_) {
242  failed_ids_.push_back(goal_index);
243  RCLCPP_WARN(
244  get_logger(), "Failed to execute task at waypoint %i "
245  " stop on failure is enabled."
246  " Terminating action.", goal_index);
247  result->missed_waypoints = failed_ids_;
248  action_server_->terminate_current(result);
249  failed_ids_.clear();
250  return;
251  } else {
252  RCLCPP_INFO(
253  get_logger(), "Handled task execution on waypoint %i,"
254  " moving to next.", goal_index);
255  }
256  }
257 
258  if (current_goal_status_ != ActionStatus::PROCESSING &&
259  current_goal_status_ != ActionStatus::UNKNOWN)
260  {
261  // Update server state
262  goal_index++;
263  new_goal = true;
264  if (goal_index >= goal->poses.size()) {
265  RCLCPP_INFO(
266  get_logger(), "Completed all %zu waypoints requested.",
267  goal->poses.size());
268  result->missed_waypoints = failed_ids_;
269  action_server_->succeeded_current(result);
270  failed_ids_.clear();
271  return;
272  }
273  } else {
274  RCLCPP_INFO_EXPRESSION(
275  get_logger(),
276  (static_cast<int>(now().seconds()) % 30 == 0),
277  "Processing waypoint %i...", goal_index);
278  }
279 
280  callback_group_executor_.spin_some();
281  r.sleep();
282  }
283 }
284 
285 void
287  const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result)
288 {
289  if (result.goal_id != future_goal_handle_.get()->get_goal_id()) {
290  RCLCPP_DEBUG(
291  get_logger(),
292  "Goal IDs do not match for the current goal handle and received result."
293  "Ignoring likely due to receiving result for an old goal.");
294  return;
295  }
296 
297  switch (result.code) {
298  case rclcpp_action::ResultCode::SUCCEEDED:
299  current_goal_status_ = ActionStatus::SUCCEEDED;
300  return;
301  case rclcpp_action::ResultCode::ABORTED:
302  current_goal_status_ = ActionStatus::FAILED;
303  return;
304  case rclcpp_action::ResultCode::CANCELED:
305  current_goal_status_ = ActionStatus::FAILED;
306  return;
307  default:
308  current_goal_status_ = ActionStatus::UNKNOWN;
309  return;
310  }
311 }
312 
313 void
315  const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal)
316 {
317  if (!goal) {
318  RCLCPP_ERROR(
319  get_logger(),
320  "navigate_to_pose action client failed to send goal to server.");
321  current_goal_status_ = ActionStatus::FAILED;
322  }
323 }
324 
325 rcl_interfaces::msg::SetParametersResult
326 WaypointFollower::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
327 {
328  // No locking required as action server is running on same single threaded executor
329  rcl_interfaces::msg::SetParametersResult result;
330 
331  for (auto parameter : parameters) {
332  const auto & type = parameter.get_type();
333  const auto & name = parameter.get_name();
334 
335  if (type == ParameterType::PARAMETER_INTEGER) {
336  if (name == "loop_rate") {
337  loop_rate_ = parameter.as_int();
338  }
339  } else if (type == ParameterType::PARAMETER_BOOL) {
340  if (name == "stop_on_failure") {
341  stop_on_failure_ = parameter.as_bool();
342  }
343  }
344  }
345 
346  result.successful = true;
347  return result;
348 }
349 
350 } // namespace nav2_waypoint_follower
351 
352 #include "rclcpp_components/register_node_macro.hpp"
353 
354 // Register the component with class_loader.
355 // This acts as a sort of entry point, allowing the component to be discoverable when its library
356 // is being loaded into a running process.
357 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_waypoint_follower::WaypointFollower)
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.
An action server that uses behavior tree for navigating a robot to its goal position.
void resultCallback(const rclcpp_action::ClientGoalHandle< ClientT >::WrappedResult &result)
Action client result callback.
~WaypointFollower()
A destructor for nav2_waypoint_follower::WaypointFollower class.
WaypointFollower(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_waypoint_follower::WaypointFollower class.
void goalResponseCallback(const rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr &goal)
Action client goal response callback.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures member variables.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets member variables.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates action server.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates action server.
void followWaypoints()
Action server callbacks.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.