Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
bt_action_node.hpp
1 // Copyright (c) 2018 Intel Corporation
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_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <chrono>
21 
22 #include "behaviortree_cpp/action_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "nav2_ros_common/node_utils.hpp"
25 #include "rclcpp_action/rclcpp_action.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 
29 namespace nav2_behavior_tree
30 {
31 
32 using namespace std::chrono_literals; // NOLINT
33 
40 template<class ActionT>
41 class BtActionNode : public BT::ActionNodeBase
42 {
43 public:
51  const std::string & xml_tag_name,
52  const std::string & action_name,
53  const BT::NodeConfiguration & conf)
54  : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name), should_send_goal_(true)
55  {
56  node_ = config().blackboard->template get<nav2::LifecycleNode::SharedPtr>("node");
57  callback_group_ = node_->create_callback_group(
58  rclcpp::CallbackGroupType::MutuallyExclusive,
59  false);
60  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
61 
62  // Get the required items from the blackboard
63  auto bt_loop_duration =
64  config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
65  getInputOrBlackboard("server_timeout", server_timeout_);
66  wait_for_service_timeout_ =
67  config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");
68 
69  // timeout should be less than bt_loop_duration to be able to finish the current tick
70  max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
71 
72  // Initialize the input and output messages
73  goal_ = typename ActionT::Goal();
74  result_ = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
75 
76  std::string remapped_action_name;
77  if (getInput("server_name", remapped_action_name)) {
78  action_name_ = remapped_action_name;
79  }
80  createActionClient(action_name_);
81 
82  // Give the derive class a chance to do any initialization
83  RCLCPP_DEBUG(node_->get_logger(), "\"%s\" BtActionNode initialized", xml_tag_name.c_str());
84  }
85 
86  BtActionNode() = delete;
87 
88  virtual ~BtActionNode()
89  {
90  }
91 
96  void createActionClient(const std::string & action_name)
97  {
98  // Now that we have the ROS node to use, create the action client for this BT action
99  action_client_ = node_->create_action_client<ActionT>(action_name, callback_group_);
100 
101  // Make sure the server is actually there before continuing
102  RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
103  if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
104  RCLCPP_ERROR(
105  node_->get_logger(), "\"%s\" action server not available after waiting for %.2fs",
106  action_name.c_str(),
107  wait_for_service_timeout_.count() / 1000.0);
108  throw std::runtime_error(
109  std::string("Action server ") + action_name +
110  std::string(" not available"));
111  }
112  }
113 
120  static BT::PortsList providedBasicPorts(BT::PortsList addition)
121  {
122  BT::PortsList basic = {
123  BT::InputPort<std::string>("server_name", "Action server name"),
124  BT::InputPort<std::chrono::milliseconds>("server_timeout")
125  };
126  basic.insert(addition.begin(), addition.end());
127 
128  return basic;
129  }
130 
135  static BT::PortsList providedPorts()
136  {
137  return providedBasicPorts({});
138  }
139 
140  // Derived classes can override any of the following methods to hook into the
141  // processing for the action: on_tick, on_wait_for_result, and on_success
142 
147  virtual void on_tick()
148  {
149  }
150 
158  virtual void on_wait_for_result(std::shared_ptr<const typename ActionT::Feedback>/*feedback*/)
159  {
160  }
161 
167  virtual BT::NodeStatus on_success()
168  {
169  return BT::NodeStatus::SUCCESS;
170  }
171 
176  virtual BT::NodeStatus on_aborted()
177  {
178  return BT::NodeStatus::FAILURE;
179  }
180 
185  virtual BT::NodeStatus on_cancelled()
186  {
187  return BT::NodeStatus::SUCCESS;
188  }
189 
194  virtual void on_timeout()
195  {
196  return;
197  }
198 
203  BT::NodeStatus tick() override
204  {
205  // first step to be done only at the beginning of the Action
206  if (!BT::isStatusActive(status())) {
207  // reset the flag to send the goal or not, allowing the user the option to set it in on_tick
208  should_send_goal_ = true;
209 
210  // Clear the input and output messages to make sure we have no leftover from previous calls
211  goal_ = typename ActionT::Goal();
212  result_ = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
213 
214  // user defined callback, may modify "should_send_goal_".
215  on_tick();
216 
217  // setting the status to RUNNING to notify the BT Loggers (if any)
218  setStatus(BT::NodeStatus::RUNNING);
219 
220  if (!should_send_goal_) {
221  return BT::NodeStatus::FAILURE;
222  }
223  send_new_goal();
224  }
225 
226  try {
227  // if new goal was sent and action server has not yet responded
228  // check the future goal handle
229  if (future_goal_handle_) {
230  auto elapsed =
231  (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
232  if (!is_future_goal_handle_complete(elapsed)) {
233  // return RUNNING if there is still some time before timeout happens
234  if (elapsed < server_timeout_) {
235  return BT::NodeStatus::RUNNING;
236  }
237  // if server has taken more time than the specified timeout value return FAILURE
238  RCLCPP_WARN(
239  node_->get_logger(),
240  "Timed out while waiting for action server to acknowledge goal request for %s",
241  action_name_.c_str());
242  future_goal_handle_.reset();
243  on_timeout();
244  return BT::NodeStatus::FAILURE;
245  }
246  }
247 
248  // The following code corresponds to the "RUNNING" loop
249  if (rclcpp::ok() && !goal_result_available_) {
250  // user defined callback. May modify the value of "goal_updated_"
251  on_wait_for_result(feedback_);
252 
253  // reset feedback to avoid stale information
254  feedback_.reset();
255 
256  auto goal_status = goal_handle_->get_status();
257  if (goal_updated_ &&
258  (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING ||
259  goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED))
260  {
261  goal_updated_ = false;
262  send_new_goal();
263  auto elapsed =
264  (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
265  if (!is_future_goal_handle_complete(elapsed)) {
266  if (elapsed < server_timeout_) {
267  return BT::NodeStatus::RUNNING;
268  }
269  RCLCPP_WARN(
270  node_->get_logger(),
271  "Timed out while waiting for action server to acknowledge goal request for %s",
272  action_name_.c_str());
273  future_goal_handle_.reset();
274  on_timeout();
275  return BT::NodeStatus::FAILURE;
276  }
277  }
278 
279  callback_group_executor_.spin_some();
280 
281  // check if, after invoking spin_some(), we finally received the result
282  if (!goal_result_available_) {
283  // Yield this Action, returning RUNNING
284  return BT::NodeStatus::RUNNING;
285  }
286  }
287  } catch (const std::runtime_error & e) {
288  if (e.what() == std::string("send_goal failed") ||
289  e.what() == std::string("Goal was rejected by the action server"))
290  {
291  // Action related failure that should not fail the tree, but the node
292  return BT::NodeStatus::FAILURE;
293  } else {
294  // Internal exception to propagate to the tree
295  throw e;
296  }
297  }
298 
299  BT::NodeStatus status;
300  switch (result_.code) {
301  case rclcpp_action::ResultCode::SUCCEEDED:
302  status = on_success();
303  break;
304 
305  case rclcpp_action::ResultCode::ABORTED:
306  status = on_aborted();
307  break;
308 
309  case rclcpp_action::ResultCode::CANCELED:
310  status = on_cancelled();
311  break;
312 
313  default:
314  throw std::logic_error("BtActionNode::Tick: invalid status value");
315  }
316 
317  goal_handle_.reset();
318  return status;
319  }
320 
325  void halt() override
326  {
327  if (should_cancel_goal()) {
328  auto future_result = action_client_->async_get_result(goal_handle_);
329  auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
330  if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
331  rclcpp::FutureReturnCode::SUCCESS)
332  {
333  RCLCPP_ERROR(
334  node_->get_logger(),
335  "Failed to cancel action server for %s", action_name_.c_str());
336  }
337 
338  if (callback_group_executor_.spin_until_future_complete(future_result, server_timeout_) !=
339  rclcpp::FutureReturnCode::SUCCESS)
340  {
341  RCLCPP_ERROR(
342  node_->get_logger(),
343  "Failed to get result for %s in node halt!", action_name_.c_str());
344  }
345 
346  on_cancelled();
347  }
348 
349  // this is probably redundant, since the parent node
350  // is supposed to call it, but we keep it, just in case
351  resetStatus();
352  }
353 
354 protected:
360  {
361  // Shut the node down if it is currently running
362  if (status() != BT::NodeStatus::RUNNING) {
363  return false;
364  }
365 
366  // No need to cancel the goal if goal handle is invalid
367  if (!goal_handle_) {
368  return false;
369  }
370 
371  callback_group_executor_.spin_some();
372  auto status = goal_handle_->get_status();
373 
374  // Check if the goal is still executing
375  return status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
376  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING;
377  }
378 
383  {
384  goal_result_available_ = false;
385  auto send_goal_options = typename nav2::ActionClient<ActionT>::SendGoalOptions();
386  send_goal_options.result_callback =
387  [this](const typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult & result) {
388  if (future_goal_handle_) {
389  RCLCPP_DEBUG(
390  node_->get_logger(),
391  "Goal result for %s available, but it hasn't received the goal response yet. "
392  "It's probably a goal result for the last goal request", action_name_.c_str());
393  return;
394  }
395 
396  // TODO(#1652): a work around until rcl_action interface is updated
397  // if goal ids are not matched, the older goal call this callback so ignore the result
398  // if matched, it must be processed (including aborted)
399  if (this->goal_handle_->get_goal_id() == result.goal_id) {
400  goal_result_available_ = true;
401  result_ = result;
402  emitWakeUpSignal();
403  }
404  };
405  send_goal_options.feedback_callback =
406  [this](typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr,
407  const std::shared_ptr<const typename ActionT::Feedback> feedback) {
408  feedback_ = feedback;
409  emitWakeUpSignal();
410  };
411 
412  future_goal_handle_ = std::make_shared<
413  std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>(
414  action_client_->async_send_goal(goal_, send_goal_options));
415  time_goal_sent_ = node_->now();
416  }
417 
424  bool is_future_goal_handle_complete(std::chrono::milliseconds & elapsed)
425  {
426  auto remaining = server_timeout_ - elapsed;
427 
428  // server has already timed out, no need to sleep
429  if (remaining <= std::chrono::milliseconds(0)) {
430  future_goal_handle_.reset();
431  return false;
432  }
433 
434  auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
435  auto result =
436  callback_group_executor_.spin_until_future_complete(*future_goal_handle_, timeout);
437  elapsed += timeout;
438 
439  if (result == rclcpp::FutureReturnCode::INTERRUPTED) {
440  future_goal_handle_.reset();
441  throw std::runtime_error("send_goal failed");
442  }
443 
444  if (result == rclcpp::FutureReturnCode::SUCCESS) {
445  goal_handle_ = future_goal_handle_->get();
446  future_goal_handle_.reset();
447  if (!goal_handle_) {
448  throw std::runtime_error("Goal was rejected by the action server");
449  }
450  return true;
451  }
452 
453  return false;
454  }
455 
460  {
461  int recovery_count = 0;
462  [[maybe_unused]] auto res = config().blackboard->get("number_recoveries", recovery_count); // NOLINT
463  recovery_count += 1;
464  config().blackboard->set("number_recoveries", recovery_count); // NOLINT
465  }
466 
467  std::string action_name_;
468  typename nav2::ActionClient<ActionT>::SharedPtr action_client_;
469 
470  // All ROS2 actions have a goal and a result
471  typename ActionT::Goal goal_;
472  bool goal_updated_{false};
473  bool goal_result_available_{false};
474  typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr goal_handle_;
475  typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult result_;
476 
477  // To handle feedback from action server
478  std::shared_ptr<const typename ActionT::Feedback> feedback_;
479 
480  // The node that will be used for any ROS operations
481  nav2::LifecycleNode::SharedPtr node_;
482  rclcpp::CallbackGroup::SharedPtr callback_group_;
483  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
484 
485  // The timeout value while waiting for response from a server when a
486  // new action goal is sent or canceled
487  std::chrono::milliseconds server_timeout_;
488 
489  // The timeout value for BT loop execution
490  std::chrono::milliseconds max_timeout_;
491 
492  // The timeout value for waiting for a service to response
493  std::chrono::milliseconds wait_for_service_timeout_;
494 
495  // To track the action server acknowledgement when a new goal is sent
496  std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>
497  future_goal_handle_;
498  rclcpp::Time time_goal_sent_;
499 
500  // Can be set in on_tick or on_wait_for_result to indicate if a goal should be sent.
501  bool should_send_goal_;
502 };
503 
504 } // namespace nav2_behavior_tree
505 
506 #endif // NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
Abstract class representing an action based BT node.
BT::NodeStatus tick() override
The main override required by a BT action.
bool is_future_goal_handle_complete(std::chrono::milliseconds &elapsed)
Function to check if the action server acknowledged a new goal.
virtual BT::NodeStatus on_cancelled()
Function to perform some user-defined operation when the action is cancelled.
virtual BT::NodeStatus on_success()
Function to perform some user-defined operation upon successful completion of the action....
void halt() override
The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 ...
virtual void on_timeout()
Function to perform work in a BT Node when the action server times out Such as setting the error code...
virtual BT::NodeStatus on_aborted()
Function to perform some user-defined operation when the action is aborted.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call pro...
virtual void on_tick()
Function to perform some user-defined operation on tick Could do dynamic checks, such as getting upda...
void createActionClient(const std::string &action_name)
Create instance of an action client.
virtual void on_wait_for_result(std::shared_ptr< const typename ActionT::Feedback >)
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been...
void send_new_goal()
Function to send new goal to action server.
BtActionNode(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::BtActionNode constructor.
static BT::PortsList providedPorts()
Creates list of BT ports.
bool should_cancel_goal()
Function to check if current goal should be cancelled.
void increment_recovery_count()
Function to increment recovery count on blackboard if this node wraps a recovery.