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