Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
bt_action_server_impl.hpp
1 // Copyright (c) 2020 Sarthak Mittal
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_SERVER_IMPL_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
17 
18 #include <chrono>
19 #include <exception>
20 #include <fstream>
21 #include <limits>
22 #include <memory>
23 #include <set>
24 #include <string>
25 #include <vector>
26 
27 #include "nav2_msgs/action/navigate_to_pose.hpp"
28 #include "nav2_behavior_tree/bt_action_server.hpp"
29 #include "nav2_ros_common/node_utils.hpp"
30 #include "rcl_action/action_server.h"
31 #include "nav2_ros_common/lifecycle_node.hpp"
32 
33 namespace nav2_behavior_tree
34 {
35 
36 template<class ActionT, class NodeT>
38  const typename NodeT::WeakPtr & parent,
39  const std::string & action_name,
40  const std::vector<std::string> & plugin_lib_names,
41  const std::string & default_bt_xml_filename,
42  OnGoalReceivedCallback on_goal_received_callback,
43  OnLoopCallback on_loop_callback,
44  OnPreemptCallback on_preempt_callback,
45  OnCompletionCallback on_completion_callback)
46 : action_name_(action_name),
47  default_bt_xml_filename_(default_bt_xml_filename),
48  plugin_lib_names_(plugin_lib_names),
49  node_(parent),
50  on_goal_received_callback_(on_goal_received_callback),
51  on_loop_callback_(on_loop_callback),
52  on_preempt_callback_(on_preempt_callback),
53  on_completion_callback_(on_completion_callback),
54  internal_error_code_(0),
55  internal_error_msg_()
56 {
57  auto node = node_.lock();
58  logger_ = node->get_logger();
59  clock_ = node->get_clock();
60 
61  // Declare this node's parameters
62  if (!node->has_parameter("bt_loop_duration")) {
63  node->declare_parameter("bt_loop_duration", 10);
64  }
65  if (!node->has_parameter("default_server_timeout")) {
66  node->declare_parameter("default_server_timeout", 20);
67  }
68  if (!node->has_parameter("always_reload_bt_xml")) {
69  node->declare_parameter("always_reload_bt_xml", false);
70  }
71  if (!node->has_parameter("wait_for_service_timeout")) {
72  node->declare_parameter("wait_for_service_timeout", 1000);
73  }
74 
75  std::vector<std::string> error_code_name_prefixes = {
76  "assisted_teleop",
77  "backup",
78  "compute_path",
79  "dock_robot",
80  "drive_on_heading",
81  "follow_path",
82  "nav_thru_poses",
83  "nav_to_pose",
84  "spin",
85  "undock_robot",
86  "wait",
87  };
88 
89  if (node->has_parameter("error_code_names")) {
90  throw std::runtime_error("parameter 'error_code_names' has been replaced by "
91  " 'error_code_name_prefixes' and MUST be removed.\n"
92  " Please review migration guide and update your configuration.");
93  }
94 
95  if (!node->has_parameter("error_code_name_prefixes")) {
96  const rclcpp::ParameterValue value = node->declare_parameter(
97  "error_code_name_prefixes",
98  rclcpp::PARAMETER_STRING_ARRAY);
99  if (value.get_type() == rclcpp::PARAMETER_NOT_SET) {
100  std::string error_code_name_prefixes_str;
101  for (const auto & error_code_name_prefix : error_code_name_prefixes) {
102  error_code_name_prefixes_str += " " + error_code_name_prefix;
103  }
104  RCLCPP_WARN_STREAM(
105  logger_, "error_code_name_prefixes parameters were not set. Using default values of:"
106  << error_code_name_prefixes_str + "\n"
107  << "Make sure these match your BT and there are not other sources of error codes you"
108  "reported to your application");
109  rclcpp::Parameter error_code_name_prefixes_param("error_code_name_prefixes",
110  error_code_name_prefixes);
111  node->set_parameter(error_code_name_prefixes_param);
112  } else {
113  error_code_name_prefixes = value.get<std::vector<std::string>>();
114  std::string error_code_name_prefixes_str;
115  for (const auto & error_code_name_prefix : error_code_name_prefixes) {
116  error_code_name_prefixes_str += " " + error_code_name_prefix;
117  }
118  RCLCPP_INFO_STREAM(logger_, "Error_code parameters were set to:"
119  << error_code_name_prefixes_str);
120  }
121  }
122 }
123 
124 template<class ActionT, class NodeT>
126 {}
127 
128 template<class ActionT, class NodeT>
130 {
131  auto node = node_.lock();
132  if (!node) {
133  throw std::runtime_error{"Failed to lock node"};
134  }
135 
136  // Name client node after action name
137  std::string client_node_name = action_name_;
138  std::replace(client_node_name.begin(), client_node_name.end(), '/', '_');
139  // Use suffix '_rclcpp_node' to keep parameter file consistency #1773
140 
141  auto new_arguments = node->get_node_options().arguments();
142  nav2::replaceOrAddArgument(new_arguments, "-r", "__node", std::string("__node:=") +
143  std::string(node->get_name()) + "_" + client_node_name + "_rclcpp_node");
144  auto options = node->get_node_options();
145  options = options.arguments(new_arguments);
146 
147  // Support for handling the topic-based goal pose from rviz
148  client_node_ = std::make_shared<nav2::LifecycleNode>("_", options);
149  client_node_->configure();
150  client_node_->activate();
151 
152  // Declare parameters for common client node applications to share with BT nodes
153  // Declare if not declared in case being used an external application, then copying
154  // all of the main node's parameters to the client for BT nodes to obtain
155  nav2::declare_parameter_if_not_declared(
156  node, "global_frame", rclcpp::ParameterValue(std::string("map")));
157  nav2::declare_parameter_if_not_declared(
158  node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
159  nav2::declare_parameter_if_not_declared(
160  node, "transform_tolerance", rclcpp::ParameterValue(0.1));
161  rclcpp::copy_all_parameter_values(node, client_node_);
162 
163  // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the subscription
164  // to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode
165  action_server_ = nav2::interfaces::create_action_server<ActionT>(
166  node, action_name_, std::bind(&BtActionServer<ActionT, NodeT>::executeCallback, this),
167  nullptr, std::chrono::milliseconds(500), false);
168 
169  // Get parameters for BT timeouts
170  int bt_loop_duration;
171  node->get_parameter("bt_loop_duration", bt_loop_duration);
172  bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
173  int default_server_timeout;
174  node->get_parameter("default_server_timeout", default_server_timeout);
175  default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);
176  int wait_for_service_timeout;
177  node->get_parameter("wait_for_service_timeout", wait_for_service_timeout);
178  wait_for_service_timeout_ = std::chrono::milliseconds(wait_for_service_timeout);
179  node->get_parameter("always_reload_bt_xml", always_reload_bt_xml_);
180 
181  // Get error code id names to grab off of the blackboard
182  error_code_name_prefixes_ = node->get_parameter("error_code_name_prefixes").as_string_array();
183 
184  // Create the class that registers our custom nodes and executes the BT
185  bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_, client_node_);
186 
187  // Create the blackboard that will be shared by all of the nodes in the tree
188  blackboard_ = BT::Blackboard::create();
189 
190  // Put items on the blackboard
191  blackboard_->set<nav2::LifecycleNode::SharedPtr>("node", client_node_); // NOLINT
192  blackboard_->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_); // NOLINT
193  blackboard_->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_); // NOLINT
194  blackboard_->set<std::chrono::milliseconds>(
195  "wait_for_service_timeout",
196  wait_for_service_timeout_);
197 
198  return true;
199 }
200 
201 template<class ActionT, class NodeT>
203 {
204  resetInternalError();
205  if (!loadBehaviorTree(default_bt_xml_filename_)) {
206  RCLCPP_ERROR(logger_, "Error loading XML file: %s", default_bt_xml_filename_.c_str());
207  return false;
208  }
209  action_server_->activate();
210  return true;
211 }
212 
213 template<class ActionT, class NodeT>
215 {
216  action_server_->deactivate();
217  return true;
218 }
219 
220 template<class ActionT, class NodeT>
222 {
223  client_node_->deactivate();
224  client_node_->cleanup();
225  client_node_.reset();
226  action_server_.reset();
227  topic_logger_.reset();
228  plugin_lib_names_.clear();
229  current_bt_xml_filename_.clear();
230  blackboard_.reset();
231  bt_->haltAllActions(tree_);
232  bt_->resetGrootMonitor();
233  bt_.reset();
234  return true;
235 }
236 
237 template<class ActionT, class NodeT>
239  const bool enable,
240  const unsigned server_port)
241 {
242  enable_groot_monitoring_ = enable;
243  groot_server_port_ = server_port;
244 }
245 
246 template<class ActionT, class NodeT>
247 bool BtActionServer<ActionT, NodeT>::loadBehaviorTree(const std::string & bt_xml_filename)
248 {
249  // Empty filename is default for backward compatibility
250  auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename;
251 
252  // Use previous BT if it is the existing one and always reload flag is not set to true
253  if (!always_reload_bt_xml_ && current_bt_xml_filename_ == filename) {
254  RCLCPP_DEBUG(logger_, "BT will not be reloaded as the given xml is already loaded");
255  return true;
256  }
257 
258  // if a new tree is created, than the Groot2 Publisher must be destroyed
259  bt_->resetGrootMonitor();
260 
261  // Read the input BT XML from the specified file into a string
262  std::ifstream xml_file(filename);
263 
264  if (!xml_file.good()) {
265  setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
266  "Couldn't open input XML file: " + filename);
267  return false;
268  }
269 
270  // Create the Behavior Tree from the XML input
271  try {
272  tree_ = bt_->createTreeFromFile(filename, blackboard_);
273  for (auto & subtree : tree_.subtrees) {
274  auto & blackboard = subtree->blackboard;
275  blackboard->set("node", client_node_);
276  blackboard->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);
277  blackboard->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);
278  blackboard->set<std::chrono::milliseconds>(
279  "wait_for_service_timeout",
280  wait_for_service_timeout_);
281  }
282  } catch (const std::exception & e) {
283  setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
284  std::string("Exception when loading BT: ") + e.what());
285  return false;
286  }
287 
288  topic_logger_ = std::make_unique<RosTopicLogger>(client_node_, tree_);
289 
290  current_bt_xml_filename_ = filename;
291 
292  // Enable monitoring with Groot2
293  if (enable_groot_monitoring_) {
294  bt_->addGrootMonitoring(&tree_, groot_server_port_);
295  RCLCPP_DEBUG(
296  logger_, "Enabling Groot2 monitoring for %s: %d",
297  action_name_.c_str(), groot_server_port_);
298  }
299 
300  return true;
301 }
302 
303 template<class ActionT, class NodeT>
305 {
306  if (!on_goal_received_callback_(action_server_->get_current_goal())) {
307  // Give server an opportunity to populate the result message
308  // if the goal is not accepted
309  auto result = std::make_shared<typename ActionT::Result>();
310  populateErrorCode(result);
311  action_server_->terminate_current(result);
312  cleanErrorCodes();
313  return;
314  }
315 
316  auto is_canceling = [&]() {
317  if (action_server_ == nullptr) {
318  RCLCPP_DEBUG(logger_, "Action server unavailable. Canceling.");
319  return true;
320  }
321  if (!action_server_->is_server_active()) {
322  RCLCPP_DEBUG(logger_, "Action server is inactive. Canceling.");
323  return true;
324  }
325  return action_server_->is_cancel_requested();
326  };
327 
328  auto on_loop = [&]() {
329  if (action_server_->is_preempt_requested() && on_preempt_callback_) {
330  on_preempt_callback_(action_server_->get_pending_goal());
331  }
332  topic_logger_->flush();
333  on_loop_callback_();
334  };
335 
336  // Execute the BT that was previously created in the configure step
337  nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling, bt_loop_duration_);
338 
339  // Make sure that the Bt is not in a running state from a previous execution
340  // note: if all the ControlNodes are implemented correctly, this is not needed.
341  bt_->haltAllActions(tree_);
342 
343  // Give server an opportunity to populate the result message or simple give
344  // an indication that the action is complete.
345  auto result = std::make_shared<typename ActionT::Result>();
346 
347  populateErrorCode(result);
348 
349  on_completion_callback_(result, rc);
350 
351  switch (rc) {
352  case nav2_behavior_tree::BtStatus::SUCCEEDED:
353  action_server_->succeeded_current(result);
354  RCLCPP_INFO(logger_, "Goal succeeded");
355  break;
356 
357  case nav2_behavior_tree::BtStatus::FAILED:
358  action_server_->terminate_current(result);
359  RCLCPP_ERROR(logger_, "Goal failed error_code:%d error_msg:'%s'", result->error_code,
360  result->error_msg.c_str());
361  break;
362 
363  case nav2_behavior_tree::BtStatus::CANCELED:
364  action_server_->terminate_all(result);
365  RCLCPP_INFO(logger_, "Goal canceled");
366  break;
367  }
368 
369  cleanErrorCodes();
370 }
371 
372 template<class ActionT, class NodeT>
374  uint16_t error_code,
375  const std::string & error_msg)
376 {
377  internal_error_code_ = error_code;
378  internal_error_msg_ = error_msg;
379  RCLCPP_ERROR(logger_, "Setting internal error error_code:%d, error_msg:%s",
380  internal_error_code_, internal_error_msg_.c_str());
381 }
382 
383 template<class ActionT, class NodeT>
385 {
386  internal_error_code_ = ActionT::Result::NONE;
387  internal_error_msg_ = "";
388 }
389 
390 template<class ActionT, class NodeT>
392  typename std::shared_ptr<typename ActionT::Result> result)
393 {
394  if (internal_error_code_ != ActionT::Result::NONE) {
395  result->error_code = internal_error_code_;
396  result->error_msg = internal_error_msg_;
397  return true;
398  }
399  return false;
400 }
401 
402 template<class ActionT, class NodeT>
404  typename std::shared_ptr<typename ActionT::Result> result)
405 {
406  int highest_priority_error_code = std::numeric_limits<int>::max();
407  std::string highest_priority_error_msg = "";
408  std::string name;
409 
410  if (internal_error_code_ != 0) {
411  highest_priority_error_code = internal_error_code_;
412  highest_priority_error_msg = internal_error_msg_;
413  }
414 
415  for (const auto & error_code_name_prefix : error_code_name_prefixes_) {
416  try {
417  name = error_code_name_prefix + "_error_code";
418  int current_error_code = blackboard_->get<int>(name);
419  if (current_error_code != 0 && current_error_code < highest_priority_error_code) {
420  highest_priority_error_code = current_error_code;
421  name = error_code_name_prefix + "_error_msg";
422  highest_priority_error_msg = blackboard_->get<std::string>(name);
423  }
424  } catch (...) {
425  RCLCPP_DEBUG(
426  logger_,
427  "Failed to get error code name: %s from blackboard",
428  name.c_str());
429  }
430  }
431 
432  if (highest_priority_error_code != std::numeric_limits<int>::max()) {
433  result->error_code = highest_priority_error_code;
434  result->error_msg = highest_priority_error_msg;
435  }
436 }
437 
438 template<class ActionT, class NodeT>
440 {
441  std::string name;
442  for (const auto & error_code_name_prefix : error_code_name_prefixes_) {
443  name = error_code_name_prefix + "_error_code";
444  blackboard_->set<unsigned short>(name, 0); //NOLINT
445  name = error_code_name_prefix + "_error_msg";
446  blackboard_->set<std::string>(name, "");
447  }
448  resetInternalError();
449 }
450 
451 } // namespace nav2_behavior_tree
452 
453 #endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
An action server that uses behavior tree to execute an action.
bool on_cleanup()
Resets member variables.
void setGrootMonitoring(const bool enable, const unsigned server_port)
Enable (or disable) Groot2 monitoring of BT.
bool loadBehaviorTree(const std::string &bt_xml_filename="")
Replace current BT with another one.
bool populateInternalError(typename std::shared_ptr< typename ActionT::Result > result)
populate result with internal error code and error_msg if not NONE
bool on_deactivate()
Deactivates action server.
~BtActionServer()
A destructor for nav2_behavior_tree::BtActionServer class.
bool on_configure()
Configures member variables Initializes action server for, builds behavior tree from xml file,...
BtActionServer(const typename NodeT::WeakPtr &parent, const std::string &action_name, const std::vector< std::string > &plugin_lib_names, const std::string &default_bt_xml_filename, OnGoalReceivedCallback on_goal_received_callback, OnLoopCallback on_loop_callback, OnPreemptCallback on_preempt_callback, OnCompletionCallback on_completion_callback)
A constructor for nav2_behavior_tree::BtActionServer class.
void resetInternalError(void)
reset internal error code and message
void executeCallback()
Action server callback.
void cleanErrorCodes()
Setting BT error codes to success. Used to clean blackboard between different BT runs.
void populateErrorCode(typename std::shared_ptr< typename ActionT::Result > result)
updates the action server result to the highest priority error code posted on the blackboard
bool on_activate()
Activates action server.
void setInternalError(uint16_t error_code, const std::string &error_msg)
Set internal error code and message.