15 #ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
27 #include "nav2_msgs/action/navigate_to_pose.hpp"
28 #include "nav2_behavior_tree/bt_action_server.hpp"
29 #include "nav2_util/node_utils.hpp"
30 #include "rcl_action/action_server.h"
31 #include "rclcpp_lifecycle/lifecycle_node.hpp"
33 namespace nav2_behavior_tree
36 template<
class ActionT>
38 const rclcpp_lifecycle::LifecycleNode::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 const std::vector<std::string> & search_directories,
43 OnGoalReceivedCallback on_goal_received_callback,
44 OnLoopCallback on_loop_callback,
45 OnPreemptCallback on_preempt_callback,
46 OnCompletionCallback on_completion_callback)
47 : action_name_(action_name),
48 default_bt_xml_filename_(default_bt_xml_filename),
49 search_directories_(search_directories),
50 plugin_lib_names_(plugin_lib_names),
52 on_goal_received_callback_(on_goal_received_callback),
53 on_loop_callback_(on_loop_callback),
54 on_preempt_callback_(on_preempt_callback),
55 on_completion_callback_(on_completion_callback),
56 internal_error_code_(0),
59 auto node = node_.lock();
60 logger_ = node->get_logger();
61 clock_ = node->get_clock();
64 if (!node->has_parameter(
"bt_loop_duration")) {
65 node->declare_parameter(
"bt_loop_duration", 10);
67 if (!node->has_parameter(
"default_server_timeout")) {
68 node->declare_parameter(
"default_server_timeout", 20);
70 if (!node->has_parameter(
"always_reload_bt_xml")) {
71 node->declare_parameter(
"always_reload_bt_xml",
false);
73 if (!node->has_parameter(
"wait_for_service_timeout")) {
74 node->declare_parameter(
"wait_for_service_timeout", 1000);
77 std::vector<std::string> error_code_name_prefixes = {
91 if (node->has_parameter(
"error_code_names")) {
92 throw std::runtime_error(
"parameter 'error_code_names' has been replaced by "
93 " 'error_code_name_prefixes' and MUST be removed.\n"
94 " Please review migration guide and update your configuration.");
97 if (!node->has_parameter(
"error_code_name_prefixes")) {
98 const rclcpp::ParameterValue value = node->declare_parameter(
99 "error_code_name_prefixes",
100 rclcpp::PARAMETER_STRING_ARRAY);
101 if (value.get_type() == rclcpp::PARAMETER_NOT_SET) {
102 std::string error_code_name_prefixes_str;
103 for (
const auto & error_code_name_prefix : error_code_name_prefixes) {
104 error_code_name_prefixes_str +=
" " + error_code_name_prefix;
107 logger_,
"error_code_name_prefixes parameters were not set. Using default values of:"
108 << error_code_name_prefixes_str +
"\n"
109 <<
"Make sure these match your BT and there are not other sources of error codes you"
110 "reported to your application");
111 rclcpp::Parameter error_code_name_prefixes_param(
"error_code_name_prefixes",
112 error_code_name_prefixes);
113 node->set_parameter(error_code_name_prefixes_param);
115 error_code_name_prefixes = value.get<std::vector<std::string>>();
116 std::string error_code_name_prefixes_str;
117 for (
const auto & error_code_name_prefix : error_code_name_prefixes) {
118 error_code_name_prefixes_str +=
" " + error_code_name_prefix;
120 RCLCPP_INFO_STREAM(logger_,
"Error_code parameters were set to:"
121 << error_code_name_prefixes_str);
126 template<
class ActionT>
130 template<
class ActionT>
133 auto node = node_.lock();
135 throw std::runtime_error{
"Failed to lock node"};
139 std::string client_node_name = action_name_;
140 std::replace(client_node_name.begin(), client_node_name.end(),
'/',
'_');
142 auto options = rclcpp::NodeOptions().arguments(
145 std::string(
"__node:=") +
146 std::string(node->get_name()) +
"_" + client_node_name +
"_rclcpp_node",
149 std::string(node->get_parameter(
"use_sim_time").as_bool() ?
"true" :
"false"),
153 client_node_ = std::make_shared<rclcpp::Node>(
"_", options);
158 nav2_util::declare_parameter_if_not_declared(
159 node,
"global_frame", rclcpp::ParameterValue(std::string(
"map")));
160 nav2_util::declare_parameter_if_not_declared(
161 node,
"robot_base_frame", rclcpp::ParameterValue(std::string(
"base_link")));
162 nav2_util::declare_parameter_if_not_declared(
163 node,
"transform_tolerance", rclcpp::ParameterValue(0.1));
164 rclcpp::copy_all_parameter_values(node, client_node_);
166 action_server_ = std::make_shared<ActionServer>(
167 node->get_node_base_interface(),
168 node->get_node_clock_interface(),
169 node->get_node_logging_interface(),
170 node->get_node_waitables_interface(),
172 nullptr, std::chrono::milliseconds(500),
false);
175 int bt_loop_duration;
176 node->get_parameter(
"bt_loop_duration", bt_loop_duration);
177 bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
178 int default_server_timeout;
179 node->get_parameter(
"default_server_timeout", default_server_timeout);
180 default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);
181 int wait_for_service_timeout;
182 node->get_parameter(
"wait_for_service_timeout", wait_for_service_timeout);
183 wait_for_service_timeout_ = std::chrono::milliseconds(wait_for_service_timeout);
184 node->get_parameter(
"always_reload_bt_xml", always_reload_bt_xml_);
187 error_code_name_prefixes_ = node->get_parameter(
"error_code_name_prefixes").as_string_array();
190 bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_, client_node_);
193 blackboard_ = BT::Blackboard::create();
196 blackboard_->set<rclcpp::Node::SharedPtr>(
"node", client_node_);
197 blackboard_->set<std::chrono::milliseconds>(
"server_timeout", default_server_timeout_);
198 blackboard_->set<std::chrono::milliseconds>(
"bt_loop_duration", bt_loop_duration_);
199 blackboard_->set<std::chrono::milliseconds>(
200 "wait_for_service_timeout",
201 wait_for_service_timeout_);
206 template<
class ActionT>
209 resetInternalError();
210 if (!loadBehaviorTree(default_bt_xml_filename_)) {
211 RCLCPP_ERROR(logger_,
"Error loading XML file: %s", default_bt_xml_filename_.c_str());
214 action_server_->activate();
218 template<
class ActionT>
221 action_server_->deactivate();
225 template<
class ActionT>
228 client_node_.reset();
229 action_server_.reset();
230 topic_logger_.reset();
231 plugin_lib_names_.clear();
232 current_bt_xml_filename_.clear();
234 bt_->haltAllActions(tree_);
235 bt_->resetGrootMonitor();
240 template<
class ActionT>
243 enable_groot_monitoring_ = enable;
244 groot_server_port_ = server_port;
247 template<
class ActionT>
250 namespace fs = std::filesystem;
253 auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename;
256 if (!always_reload_bt_xml_ && current_bt_xml_filename_ == filename) {
257 RCLCPP_DEBUG(logger_,
"BT will not be reloaded as the given xml is already loaded");
262 bt_->resetGrootMonitor();
264 std::ifstream xml_file(filename);
265 if (!xml_file.good()) {
266 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
267 "Couldn't open BT XML file: " + filename);
271 const auto canonical_main_bt = fs::canonical(filename);
274 for (
const auto & directory : search_directories_) {
276 for (
const auto & entry : fs::directory_iterator(directory)) {
277 if (entry.path().extension() ==
".xml") {
279 if (fs::equivalent(fs::canonical(entry.path()), canonical_main_bt)) {
282 bt_->registerTreeFromFile(entry.path().string());
285 }
catch (
const std::exception & e) {
286 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
287 "Exception reading behavior tree directory: " + std::string(e.what()));
294 tree_ = bt_->createTreeFromFile(filename, blackboard_);
295 for (
auto & subtree : tree_.subtrees) {
296 auto & blackboard = subtree->blackboard;
297 blackboard->set(
"node", client_node_);
298 blackboard->set<std::chrono::milliseconds>(
"server_timeout", default_server_timeout_);
299 blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration", bt_loop_duration_);
300 blackboard->set<std::chrono::milliseconds>(
301 "wait_for_service_timeout",
302 wait_for_service_timeout_);
304 }
catch (
const std::exception & e) {
305 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
306 std::string(
"Exception when creating BT tree from file: ") + e.what());
311 topic_logger_ = std::make_unique<RosTopicLogger>(client_node_, tree_);
313 current_bt_xml_filename_ = filename;
315 if (enable_groot_monitoring_) {
316 bt_->addGrootMonitoring(&tree_, groot_server_port_);
318 logger_,
"Enabling Groot2 monitoring for %s: %d",
319 action_name_.c_str(), groot_server_port_);
325 template<
class ActionT>
328 if (!on_goal_received_callback_(action_server_->get_current_goal())) {
331 auto result = std::make_shared<typename ActionT::Result>();
332 populateErrorCode(result);
333 action_server_->terminate_current(result);
338 auto is_canceling = [&]() {
339 if (action_server_ ==
nullptr) {
340 RCLCPP_DEBUG(logger_,
"Action server unavailable. Canceling.");
343 if (!action_server_->is_server_active()) {
344 RCLCPP_DEBUG(logger_,
"Action server is inactive. Canceling.");
347 return action_server_->is_cancel_requested();
350 auto on_loop = [&]() {
351 if (action_server_->is_preempt_requested() && on_preempt_callback_) {
352 on_preempt_callback_(action_server_->get_pending_goal());
354 topic_logger_->flush();
359 nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling, bt_loop_duration_);
363 bt_->haltAllActions(tree_);
367 auto result = std::make_shared<typename ActionT::Result>();
369 populateErrorCode(result);
371 on_completion_callback_(result, rc);
374 case nav2_behavior_tree::BtStatus::SUCCEEDED:
375 action_server_->succeeded_current(result);
376 RCLCPP_INFO(logger_,
"Goal succeeded");
379 case nav2_behavior_tree::BtStatus::FAILED:
380 action_server_->terminate_current(result);
381 RCLCPP_ERROR(logger_,
"Goal failed error_code:%d error_msg:'%s'", result->error_code,
382 result->error_msg.c_str());
385 case nav2_behavior_tree::BtStatus::CANCELED:
386 action_server_->terminate_all(result);
387 RCLCPP_INFO(logger_,
"Goal canceled");
394 template<
class ActionT>
397 internal_error_code_ = error_code;
398 internal_error_msg_ = error_msg;
399 RCLCPP_ERROR(logger_,
"Setting internal error error_code:%d, error_msg:%s",
400 internal_error_code_, internal_error_msg_.c_str());
403 template<
class ActionT>
406 internal_error_code_ = ActionT::Result::NONE;
407 internal_error_msg_ =
"";
410 template<
class ActionT>
412 typename std::shared_ptr<typename ActionT::Result> result)
414 if (internal_error_code_ != ActionT::Result::NONE) {
415 result->error_code = internal_error_code_;
416 result->error_msg = internal_error_msg_;
422 template<
class ActionT>
424 typename std::shared_ptr<typename ActionT::Result> result)
426 int highest_priority_error_code = std::numeric_limits<int>::max();
427 std::string highest_priority_error_msg =
"";
430 if (internal_error_code_ != 0) {
431 highest_priority_error_code = internal_error_code_;
432 highest_priority_error_msg = internal_error_msg_;
435 for (
const auto & error_code_name_prefix : error_code_name_prefixes_) {
437 name = error_code_name_prefix +
"_error_code";
438 int current_error_code = blackboard_->get<
int>(name);
439 if (current_error_code != 0 && current_error_code < highest_priority_error_code) {
440 highest_priority_error_code = current_error_code;
441 name = error_code_name_prefix +
"_error_msg";
442 highest_priority_error_msg = blackboard_->get<std::string>(name);
447 "Failed to get error code name: %s from blackboard",
452 if (highest_priority_error_code != std::numeric_limits<int>::max()) {
453 result->error_code = highest_priority_error_code;
454 result->error_msg = highest_priority_error_msg;
458 template<
class ActionT>
462 for (
const auto & error_code_name_prefix : error_code_name_prefixes_) {
463 name = error_code_name_prefix +
"_error_code";
464 blackboard_->set<
unsigned short>(name, 0);
465 name = error_code_name_prefix +
"_error_msg";
466 blackboard_->set<std::string>(name,
"");
468 resetInternalError();
An action server that uses behavior tree to execute an action.
bool populateInternalError(typename std::shared_ptr< typename ActionT::Result > result)
populate result with internal error code and error_msg if not NONE
bool loadBehaviorTree(const std::string &bt_xml_filename="")
Replace current BT with another one.
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, const std::vector< std::string > &search_directories, 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.
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.
void resetInternalError(void)
reset internal error code and message
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.
void setGrootMonitoring(const bool enable, const unsigned server_port)
Enable (or disable) Groot2 monitoring of BT.
void setInternalError(uint16_t error_code, const std::string &error_msg)
Set internal error code and message.
bool on_configure()
Configures member variables Initializes action server for, builds behavior tree from xml file,...