Nav2 Navigation Stack - jazzy  jazzy
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 <memory>
19 #include <string>
20 #include <fstream>
21 #include <set>
22 #include <exception>
23 #include <vector>
24 #include <limits>
25 
26 #include "nav2_msgs/action/navigate_to_pose.hpp"
27 #include "nav2_behavior_tree/bt_action_server.hpp"
28 #include "ament_index_cpp/get_package_share_directory.hpp"
29 #include "nav2_util/node_utils.hpp"
30 
31 namespace nav2_behavior_tree
32 {
33 
34 template<class ActionT>
36  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
37  const std::string & action_name,
38  const std::vector<std::string> & plugin_lib_names,
39  const std::string & default_bt_xml_filename,
40  OnGoalReceivedCallback on_goal_received_callback,
41  OnLoopCallback on_loop_callback,
42  OnPreemptCallback on_preempt_callback,
43  OnCompletionCallback on_completion_callback)
44 : action_name_(action_name),
45  default_bt_xml_filename_(default_bt_xml_filename),
46  plugin_lib_names_(plugin_lib_names),
47  node_(parent),
48  on_goal_received_callback_(on_goal_received_callback),
49  on_loop_callback_(on_loop_callback),
50  on_preempt_callback_(on_preempt_callback),
51  on_completion_callback_(on_completion_callback)
52 {
53  auto node = node_.lock();
54  logger_ = node->get_logger();
55  clock_ = node->get_clock();
56 
57  // Declare this node's parameters
58  if (!node->has_parameter("bt_loop_duration")) {
59  node->declare_parameter("bt_loop_duration", 10);
60  }
61  if (!node->has_parameter("default_server_timeout")) {
62  node->declare_parameter("default_server_timeout", 20);
63  }
64  if (!node->has_parameter("action_server_result_timeout")) {
65  node->declare_parameter("action_server_result_timeout", 900.0);
66  }
67  if (!node->has_parameter("always_reload_bt_xml")) {
68  node->declare_parameter("always_reload_bt_xml", false);
69  }
70  if (!node->has_parameter("wait_for_service_timeout")) {
71  node->declare_parameter("wait_for_service_timeout", 1000);
72  }
73 
74  std::vector<std::string> error_code_names = {
75  "follow_path_error_code",
76  "compute_path_error_code"
77  };
78 
79  if (!node->has_parameter("error_code_names")) {
80  const rclcpp::ParameterValue value = node->declare_parameter(
81  "error_code_names",
82  rclcpp::PARAMETER_STRING_ARRAY);
83  if (value.get_type() == rclcpp::PARAMETER_NOT_SET) {
84  std::string error_codes_str;
85  for (const auto & error_code : error_code_names) {
86  error_codes_str += " " + error_code;
87  }
88  RCLCPP_WARN_STREAM(
89  logger_, "Error_code parameters were not set. Using default values of:"
90  << error_codes_str + "\n"
91  << "Make sure these match your BT and there are not other sources of error codes you"
92  "reported to your application");
93  rclcpp::Parameter error_code_names_param("error_code_names", error_code_names);
94  node->set_parameter(error_code_names_param);
95  } else {
96  error_code_names = value.get<std::vector<std::string>>();
97  std::string error_codes_str;
98  for (const auto & error_code : error_code_names) {
99  error_codes_str += " " + error_code;
100  }
101  RCLCPP_INFO_STREAM(logger_, "Error_code parameters were set to:" << error_codes_str);
102  }
103  }
104 }
105 
106 template<class ActionT>
108 {}
109 
110 template<class ActionT>
112 {
113  auto node = node_.lock();
114  if (!node) {
115  throw std::runtime_error{"Failed to lock node"};
116  }
117 
118  // Name client node after action name
119  std::string client_node_name = action_name_;
120  std::replace(client_node_name.begin(), client_node_name.end(), '/', '_');
121  // Use suffix '_rclcpp_node' to keep parameter file consistency #1773
122  auto options = rclcpp::NodeOptions().arguments(
123  {"--ros-args",
124  "-r",
125  std::string("__node:=") +
126  std::string(node->get_name()) + "_" + client_node_name + "_rclcpp_node",
127  "-p",
128  "use_sim_time:=" +
129  std::string(node->get_parameter("use_sim_time").as_bool() ? "true" : "false"),
130  "--"});
131 
132  // Support for handling the topic-based goal pose from rviz
133  client_node_ = std::make_shared<rclcpp::Node>("_", options);
134 
135  // Declare parameters for common client node applications to share with BT nodes
136  // Declare if not declared in case being used an external application, then copying
137  // all of the main node's parameters to the client for BT nodes to obtain
138  nav2_util::declare_parameter_if_not_declared(
139  node, "global_frame", rclcpp::ParameterValue(std::string("map")));
140  nav2_util::declare_parameter_if_not_declared(
141  node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
142  nav2_util::declare_parameter_if_not_declared(
143  node, "transform_tolerance", rclcpp::ParameterValue(0.1));
144  rclcpp::copy_all_parameter_values(node, client_node_);
145 
146  // set the timeout in seconds for the action server to discard goal handles if not finished
147  double action_server_result_timeout =
148  node->get_parameter("action_server_result_timeout").as_double();
149  rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
150  server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
151 
152  action_server_ = std::make_shared<ActionServer>(
153  node->get_node_base_interface(),
154  node->get_node_clock_interface(),
155  node->get_node_logging_interface(),
156  node->get_node_waitables_interface(),
157  action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this),
158  nullptr, std::chrono::milliseconds(500), false, server_options);
159 
160  // Get parameters for BT timeouts
161  int bt_loop_duration;
162  node->get_parameter("bt_loop_duration", bt_loop_duration);
163  bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
164  int default_server_timeout;
165  node->get_parameter("default_server_timeout", default_server_timeout);
166  default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);
167  int wait_for_service_timeout;
168  node->get_parameter("wait_for_service_timeout", wait_for_service_timeout);
169  wait_for_service_timeout_ = std::chrono::milliseconds(wait_for_service_timeout);
170  node->get_parameter("always_reload_bt_xml", always_reload_bt_xml_);
171 
172  // Get error code id names to grab off of the blackboard
173  error_code_names_ = node->get_parameter("error_code_names").as_string_array();
174 
175  // Create the class that registers our custom nodes and executes the BT
176  bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_, client_node_);
177 
178  // Create the blackboard that will be shared by all of the nodes in the tree
179  blackboard_ = BT::Blackboard::create();
180 
181  // Put items on the blackboard
182  blackboard_->set<rclcpp::Node::SharedPtr>("node", client_node_); // NOLINT
183  blackboard_->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_); // NOLINT
184  blackboard_->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_); // NOLINT
185  blackboard_->set<std::chrono::milliseconds>(
186  "wait_for_service_timeout",
187  wait_for_service_timeout_);
188 
189  return true;
190 }
191 
192 template<class ActionT>
194 {
195  if (!loadBehaviorTree(default_bt_xml_filename_)) {
196  RCLCPP_ERROR(logger_, "Error loading XML file: %s", default_bt_xml_filename_.c_str());
197  return false;
198  }
199  action_server_->activate();
200  return true;
201 }
202 
203 template<class ActionT>
205 {
206  action_server_->deactivate();
207  return true;
208 }
209 
210 template<class ActionT>
212 {
213  client_node_.reset();
214  action_server_.reset();
215  topic_logger_.reset();
216  plugin_lib_names_.clear();
217  current_bt_xml_filename_.clear();
218  blackboard_.reset();
219  bt_->haltAllActions(tree_);
220  bt_.reset();
221  return true;
222 }
223 
224 template<class ActionT>
225 bool BtActionServer<ActionT>::loadBehaviorTree(const std::string & bt_xml_filename)
226 {
227  // Empty filename is default for backward compatibility
228  auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename;
229 
230  // Use previous BT if it is the existing one and always reload flag is not set to true
231  if (!always_reload_bt_xml_ && current_bt_xml_filename_ == filename) {
232  RCLCPP_DEBUG(logger_, "BT will not be reloaded as the given xml is already loaded");
233  return true;
234  }
235 
236  // Read the input BT XML from the specified file into a string
237  std::ifstream xml_file(filename);
238 
239  if (!xml_file.good()) {
240  RCLCPP_ERROR(logger_, "Couldn't open input XML file: %s", filename.c_str());
241  return false;
242  }
243 
244  // Create the Behavior Tree from the XML input
245  try {
246  tree_ = bt_->createTreeFromFile(filename, blackboard_);
247  for (auto & subtree : tree_.subtrees) {
248  auto & blackboard = subtree->blackboard;
249  blackboard->set("node", client_node_);
250  blackboard->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);
251  blackboard->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);
252  blackboard->set<std::chrono::milliseconds>(
253  "wait_for_service_timeout",
254  wait_for_service_timeout_);
255  }
256  } catch (const std::exception & e) {
257  RCLCPP_ERROR(logger_, "Exception when loading BT: %s", e.what());
258  return false;
259  }
260 
261  topic_logger_ = std::make_unique<RosTopicLogger>(client_node_, tree_);
262 
263  current_bt_xml_filename_ = filename;
264  return true;
265 }
266 
267 template<class ActionT>
269 {
270  if (!on_goal_received_callback_(action_server_->get_current_goal())) {
271  action_server_->terminate_current();
272  cleanErrorCodes();
273  return;
274  }
275 
276  auto is_canceling = [&]() {
277  if (action_server_ == nullptr) {
278  RCLCPP_DEBUG(logger_, "Action server unavailable. Canceling.");
279  return true;
280  }
281  if (!action_server_->is_server_active()) {
282  RCLCPP_DEBUG(logger_, "Action server is inactive. Canceling.");
283  return true;
284  }
285  return action_server_->is_cancel_requested();
286  };
287 
288  auto on_loop = [&]() {
289  if (action_server_->is_preempt_requested() && on_preempt_callback_) {
290  on_preempt_callback_(action_server_->get_pending_goal());
291  }
292  topic_logger_->flush();
293  on_loop_callback_();
294  };
295 
296  // Execute the BT that was previously created in the configure step
297  nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling, bt_loop_duration_);
298 
299  // Make sure that the Bt is not in a running state from a previous execution
300  // note: if all the ControlNodes are implemented correctly, this is not needed.
301  bt_->haltAllActions(tree_);
302 
303  // Give server an opportunity to populate the result message or simple give
304  // an indication that the action is complete.
305  auto result = std::make_shared<typename ActionT::Result>();
306 
307  populateErrorCode(result);
308 
309  on_completion_callback_(result, rc);
310 
311  switch (rc) {
312  case nav2_behavior_tree::BtStatus::SUCCEEDED:
313  action_server_->succeeded_current(result);
314  RCLCPP_INFO(logger_, "Goal succeeded");
315  break;
316 
317  case nav2_behavior_tree::BtStatus::FAILED:
318  action_server_->terminate_current(result);
319  RCLCPP_ERROR(logger_, "Goal failed");
320  break;
321 
322  case nav2_behavior_tree::BtStatus::CANCELED:
323  action_server_->terminate_all(result);
324  RCLCPP_INFO(logger_, "Goal canceled");
325  break;
326  }
327 
328  cleanErrorCodes();
329 }
330 
331 template<class ActionT>
333  typename std::shared_ptr<typename ActionT::Result> result)
334 {
335  int highest_priority_error_code = std::numeric_limits<int>::max();
336  for (const auto & error_code : error_code_names_) {
337  try {
338  int current_error_code = blackboard_->get<int>(error_code);
339  if (current_error_code != 0 && current_error_code < highest_priority_error_code) {
340  highest_priority_error_code = current_error_code;
341  }
342  } catch (...) {
343  RCLCPP_DEBUG(
344  logger_,
345  "Failed to get error code: %s from blackboard",
346  error_code.c_str());
347  }
348  }
349 
350  if (highest_priority_error_code != std::numeric_limits<int>::max()) {
351  result->error_code = highest_priority_error_code;
352  }
353 }
354 
355 template<class ActionT>
357 {
358  for (const auto & error_code : error_code_names_) {
359  blackboard_->set<unsigned short>(error_code, 0); //NOLINT
360  }
361 }
362 
363 } // namespace nav2_behavior_tree
364 
365 #endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
An action server that uses behavior tree to execute an action.
bool loadBehaviorTree(const std::string &bt_xml_filename="")
Replace current BT with another one.
bool on_cleanup()
Resets member variables.
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
~BtActionServer()
A destructor for nav2_behavior_tree::BtActionServer class.
BtActionServer(const rclcpp_lifecycle::LifecycleNode::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 executeCallback()
Action server callback.
bool on_activate()
Activates action server.
bool on_deactivate()
Deactivates action server.
void cleanErrorCodes()
Setting BT error codes to success. Used to clean blackboard between different BT runs.
bool on_configure()
Configures member variables Initializes action server for, builds behavior tree from xml file,...