Nav2 Navigation Stack - jazzy  jazzy
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 "nav2_util/node_utils.hpp"
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "nav2_behavior_tree/bt_utils.hpp"
26 
27 namespace nav2_behavior_tree
28 {
29 
30 using namespace std::chrono_literals; // NOLINT
31 
36 template<class ActionT>
37 class BtActionNode : public BT::ActionNodeBase
38 {
39 public:
47  const std::string & xml_tag_name,
48  const std::string & action_name,
49  const BT::NodeConfiguration & conf)
50  : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name), should_send_goal_(true)
51  {
52  node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
53  callback_group_ = node_->create_callback_group(
54  rclcpp::CallbackGroupType::MutuallyExclusive,
55  false);
56  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
57 
58  // Get the required items from the blackboard
59  auto bt_loop_duration =
60  config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
61  getInputOrBlackboard("server_timeout", server_timeout_);
62  wait_for_service_timeout_ =
63  config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");
64 
65  // timeout should be less than bt_loop_duration to be able to finish the current tick
66  max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
67 
68  // Initialize the input and output messages
69  goal_ = typename ActionT::Goal();
70  result_ = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
71 
72  std::string remapped_action_name;
73  if (getInput("server_name", remapped_action_name)) {
74  action_name_ = remapped_action_name;
75  }
76  createActionClient(action_name_);
77 
78  // Give the derive class a chance to do any initialization
79  RCLCPP_DEBUG(node_->get_logger(), "\"%s\" BtActionNode initialized", xml_tag_name.c_str());
80  }
81 
82  BtActionNode() = delete;
83 
84  virtual ~BtActionNode()
85  {
86  }
87 
92  void createActionClient(const std::string & action_name)
93  {
94  // Now that we have the ROS node to use, create the action client for this BT action
95  action_client_ = rclcpp_action::create_client<ActionT>(node_, action_name, callback_group_);
96 
97  // Make sure the server is actually there before continuing
98  RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
99  if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
100  RCLCPP_ERROR(
101  node_->get_logger(), "\"%s\" action server not available after waiting for %.2fs",
102  action_name.c_str(),
103  wait_for_service_timeout_.count() / 1000.0);
104  throw std::runtime_error(
105  std::string("Action server ") + action_name +
106  std::string(" not available"));
107  }
108  }
109 
116  static BT::PortsList providedBasicPorts(BT::PortsList addition)
117  {
118  BT::PortsList basic = {
119  BT::InputPort<std::string>("server_name", "Action server name"),
120  BT::InputPort<std::chrono::milliseconds>("server_timeout")
121  };
122  basic.insert(addition.begin(), addition.end());
123 
124  return basic;
125  }
126 
131  static BT::PortsList providedPorts()
132  {
133  return providedBasicPorts({});
134  }
135 
136  // Derived classes can override any of the following methods to hook into the
137  // processing for the action: on_tick, on_wait_for_result, and on_success
138 
143  virtual void on_tick()
144  {
145  }
146 
154  virtual void on_wait_for_result(std::shared_ptr<const typename ActionT::Feedback>/*feedback*/)
155  {
156  }
157 
163  virtual BT::NodeStatus on_success()
164  {
165  return BT::NodeStatus::SUCCESS;
166  }
167 
172  virtual BT::NodeStatus on_aborted()
173  {
174  return BT::NodeStatus::FAILURE;
175  }
176 
181  virtual BT::NodeStatus on_cancelled()
182  {
183  return BT::NodeStatus::SUCCESS;
184  }
185 
190  BT::NodeStatus tick() override
191  {
192  // first step to be done only at the beginning of the Action
193  if (!BT::isStatusActive(status())) {
194  // reset the flag to send the goal or not, allowing the user the option to set it in on_tick
195  should_send_goal_ = true;
196 
197  // Clear the input and output messages to make sure we have no leftover from previous calls
198  goal_ = typename ActionT::Goal();
199  result_ = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
200 
201  // user defined callback, may modify "should_send_goal_".
202  on_tick();
203 
204  // setting the status to RUNNING to notify the BT Loggers (if any)
205  setStatus(BT::NodeStatus::RUNNING);
206 
207  if (!should_send_goal_) {
208  return BT::NodeStatus::FAILURE;
209  }
210  send_new_goal();
211  }
212 
213  try {
214  // if new goal was sent and action server has not yet responded
215  // check the future goal handle
216  if (future_goal_handle_) {
217  auto elapsed =
218  (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
219  if (!is_future_goal_handle_complete(elapsed)) {
220  // return RUNNING if there is still some time before timeout happens
221  if (elapsed < server_timeout_) {
222  return BT::NodeStatus::RUNNING;
223  }
224  // if server has taken more time than the specified timeout value return FAILURE
225  RCLCPP_WARN(
226  node_->get_logger(),
227  "Timed out while waiting for action server to acknowledge goal request for %s",
228  action_name_.c_str());
229  future_goal_handle_.reset();
230  return BT::NodeStatus::FAILURE;
231  }
232  }
233 
234  // The following code corresponds to the "RUNNING" loop
235  if (rclcpp::ok() && !goal_result_available_) {
236  // user defined callback. May modify the value of "goal_updated_"
237  on_wait_for_result(feedback_);
238 
239  // reset feedback to avoid stale information
240  feedback_.reset();
241 
242  auto goal_status = goal_handle_->get_status();
243  if (goal_updated_ &&
244  (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING ||
245  goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED))
246  {
247  goal_updated_ = false;
248  send_new_goal();
249  auto elapsed =
250  (node_->now() - time_goal_sent_).template to_chrono<std::chrono::milliseconds>();
251  if (!is_future_goal_handle_complete(elapsed)) {
252  if (elapsed < server_timeout_) {
253  return BT::NodeStatus::RUNNING;
254  }
255  RCLCPP_WARN(
256  node_->get_logger(),
257  "Timed out while waiting for action server to acknowledge goal request for %s",
258  action_name_.c_str());
259  future_goal_handle_.reset();
260  return BT::NodeStatus::FAILURE;
261  }
262  }
263 
264  callback_group_executor_.spin_some();
265 
266  // check if, after invoking spin_some(), we finally received the result
267  if (!goal_result_available_) {
268  // Yield this Action, returning RUNNING
269  return BT::NodeStatus::RUNNING;
270  }
271  }
272  } catch (const std::runtime_error & e) {
273  if (e.what() == std::string("send_goal failed") ||
274  e.what() == std::string("Goal was rejected by the action server"))
275  {
276  // Action related failure that should not fail the tree, but the node
277  return BT::NodeStatus::FAILURE;
278  } else {
279  // Internal exception to propagate to the tree
280  throw e;
281  }
282  }
283 
284  BT::NodeStatus status;
285  switch (result_.code) {
286  case rclcpp_action::ResultCode::SUCCEEDED:
287  status = on_success();
288  break;
289 
290  case rclcpp_action::ResultCode::ABORTED:
291  status = on_aborted();
292  break;
293 
294  case rclcpp_action::ResultCode::CANCELED:
295  status = on_cancelled();
296  break;
297 
298  default:
299  throw std::logic_error("BtActionNode::Tick: invalid status value");
300  }
301 
302  goal_handle_.reset();
303  return status;
304  }
305 
310  void halt() override
311  {
312  if (should_cancel_goal()) {
313  auto future_result = action_client_->async_get_result(goal_handle_);
314  auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
315  if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
316  rclcpp::FutureReturnCode::SUCCESS)
317  {
318  RCLCPP_ERROR(
319  node_->get_logger(),
320  "Failed to cancel action server for %s", action_name_.c_str());
321  }
322 
323  if (callback_group_executor_.spin_until_future_complete(future_result, server_timeout_) !=
324  rclcpp::FutureReturnCode::SUCCESS)
325  {
326  RCLCPP_ERROR(
327  node_->get_logger(),
328  "Failed to get result for %s in node halt!", action_name_.c_str());
329  }
330 
331  on_cancelled();
332  }
333 
334  // this is probably redundant, since the parent node
335  // is supposed to call it, but we keep it, just in case
336  resetStatus();
337  }
338 
339 protected:
345  {
346  // Shut the node down if it is currently running
347  if (status() != BT::NodeStatus::RUNNING) {
348  return false;
349  }
350 
351  // No need to cancel the goal if goal handle is invalid
352  if (!goal_handle_) {
353  return false;
354  }
355 
356  callback_group_executor_.spin_some();
357  auto status = goal_handle_->get_status();
358 
359  // Check if the goal is still executing
360  return status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
361  status == action_msgs::msg::GoalStatus::STATUS_EXECUTING;
362  }
363 
368  {
369  goal_result_available_ = false;
370  auto send_goal_options = typename rclcpp_action::Client<ActionT>::SendGoalOptions();
371  send_goal_options.result_callback =
372  [this](const typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult & result) {
373  if (future_goal_handle_) {
374  RCLCPP_DEBUG(
375  node_->get_logger(),
376  "Goal result for %s available, but it hasn't received the goal response yet. "
377  "It's probably a goal result for the last goal request", action_name_.c_str());
378  return;
379  }
380 
381  // TODO(#1652): a work around until rcl_action interface is updated
382  // if goal ids are not matched, the older goal call this callback so ignore the result
383  // if matched, it must be processed (including aborted)
384  if (this->goal_handle_->get_goal_id() == result.goal_id) {
385  goal_result_available_ = true;
386  result_ = result;
387  emitWakeUpSignal();
388  }
389  };
390  send_goal_options.feedback_callback =
391  [this](typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr,
392  const std::shared_ptr<const typename ActionT::Feedback> feedback) {
393  feedback_ = feedback;
394  emitWakeUpSignal();
395  };
396 
397  future_goal_handle_ = std::make_shared<
398  std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>(
399  action_client_->async_send_goal(goal_, send_goal_options));
400  time_goal_sent_ = node_->now();
401  }
402 
409  bool is_future_goal_handle_complete(std::chrono::milliseconds & elapsed)
410  {
411  auto remaining = server_timeout_ - elapsed;
412 
413  // server has already timed out, no need to sleep
414  if (remaining <= std::chrono::milliseconds(0)) {
415  future_goal_handle_.reset();
416  return false;
417  }
418 
419  auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
420  auto result =
421  callback_group_executor_.spin_until_future_complete(*future_goal_handle_, timeout);
422  elapsed += timeout;
423 
424  if (result == rclcpp::FutureReturnCode::INTERRUPTED) {
425  future_goal_handle_.reset();
426  throw std::runtime_error("send_goal failed");
427  }
428 
429  if (result == rclcpp::FutureReturnCode::SUCCESS) {
430  goal_handle_ = future_goal_handle_->get();
431  future_goal_handle_.reset();
432  if (!goal_handle_) {
433  throw std::runtime_error("Goal was rejected by the action server");
434  }
435  return true;
436  }
437 
438  return false;
439  }
440 
445  {
446  int recovery_count = 0;
447  [[maybe_unused]] auto res = config().blackboard->get("number_recoveries", recovery_count); // NOLINT
448  recovery_count += 1;
449  config().blackboard->set("number_recoveries", recovery_count); // NOLINT
450  }
451 
452  std::string action_name_;
453  typename std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_;
454 
455  // All ROS2 actions have a goal and a result
456  typename ActionT::Goal goal_;
457  bool goal_updated_{false};
458  bool goal_result_available_{false};
459  typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr goal_handle_;
460  typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult result_;
461 
462  // To handle feedback from action server
463  std::shared_ptr<const typename ActionT::Feedback> feedback_;
464 
465  // The node that will be used for any ROS operations
466  rclcpp::Node::SharedPtr node_;
467  rclcpp::CallbackGroup::SharedPtr callback_group_;
468  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
469 
470  // The timeout value while waiting for response from a server when a
471  // new action goal is sent or canceled
472  std::chrono::milliseconds server_timeout_;
473 
474  // The timeout value for BT loop execution
475  std::chrono::milliseconds max_timeout_;
476 
477  // The timeout value for waiting for a service to response
478  std::chrono::milliseconds wait_for_service_timeout_;
479 
480  // To track the action server acknowledgement when a new goal is sent
481  std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>
482  future_goal_handle_;
483  rclcpp::Time time_goal_sent_;
484 
485  // Can be set in on_tick or on_wait_for_result to indicate if a goal should be sent.
486  bool should_send_goal_;
487 };
488 
489 } // namespace nav2_behavior_tree
490 
491 #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 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.