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 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),
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),
57 auto node = node_.lock();
58 logger_ = node->get_logger();
59 clock_ = node->get_clock();
62 if (!node->has_parameter(
"bt_loop_duration")) {
63 node->declare_parameter(
"bt_loop_duration", 10);
65 if (!node->has_parameter(
"default_server_timeout")) {
66 node->declare_parameter(
"default_server_timeout", 20);
68 if (!node->has_parameter(
"always_reload_bt_xml")) {
69 node->declare_parameter(
"always_reload_bt_xml",
false);
71 if (!node->has_parameter(
"wait_for_service_timeout")) {
72 node->declare_parameter(
"wait_for_service_timeout", 1000);
75 std::vector<std::string> error_code_name_prefixes = {
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.");
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;
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);
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;
118 RCLCPP_INFO_STREAM(logger_,
"Error_code parameters were set to:"
119 << error_code_name_prefixes_str);
124 template<
class ActionT>
128 template<
class ActionT>
131 auto node = node_.lock();
133 throw std::runtime_error{
"Failed to lock node"};
137 std::string client_node_name = action_name_;
138 std::replace(client_node_name.begin(), client_node_name.end(),
'/',
'_');
140 auto options = rclcpp::NodeOptions().arguments(
143 std::string(
"__node:=") +
144 std::string(node->get_name()) +
"_" + client_node_name +
"_rclcpp_node",
147 std::string(node->get_parameter(
"use_sim_time").as_bool() ?
"true" :
"false"),
151 client_node_ = std::make_shared<rclcpp::Node>(
"_", options);
156 nav2_util::declare_parameter_if_not_declared(
157 node,
"global_frame", rclcpp::ParameterValue(std::string(
"map")));
158 nav2_util::declare_parameter_if_not_declared(
159 node,
"robot_base_frame", rclcpp::ParameterValue(std::string(
"base_link")));
160 nav2_util::declare_parameter_if_not_declared(
161 node,
"transform_tolerance", rclcpp::ParameterValue(0.1));
162 rclcpp::copy_all_parameter_values(node, client_node_);
164 action_server_ = std::make_shared<ActionServer>(
165 node->get_node_base_interface(),
166 node->get_node_clock_interface(),
167 node->get_node_logging_interface(),
168 node->get_node_waitables_interface(),
170 nullptr, std::chrono::milliseconds(500),
false);
173 int bt_loop_duration;
174 node->get_parameter(
"bt_loop_duration", bt_loop_duration);
175 bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
176 int default_server_timeout;
177 node->get_parameter(
"default_server_timeout", default_server_timeout);
178 default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);
179 int wait_for_service_timeout;
180 node->get_parameter(
"wait_for_service_timeout", wait_for_service_timeout);
181 wait_for_service_timeout_ = std::chrono::milliseconds(wait_for_service_timeout);
182 node->get_parameter(
"always_reload_bt_xml", always_reload_bt_xml_);
185 error_code_name_prefixes_ = node->get_parameter(
"error_code_name_prefixes").as_string_array();
188 bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_, client_node_);
191 blackboard_ = BT::Blackboard::create();
194 blackboard_->set<rclcpp::Node::SharedPtr>(
"node", client_node_);
195 blackboard_->set<std::chrono::milliseconds>(
"server_timeout", default_server_timeout_);
196 blackboard_->set<std::chrono::milliseconds>(
"bt_loop_duration", bt_loop_duration_);
197 blackboard_->set<std::chrono::milliseconds>(
198 "wait_for_service_timeout",
199 wait_for_service_timeout_);
204 template<
class ActionT>
207 resetInternalError();
208 if (!loadBehaviorTree(default_bt_xml_filename_)) {
209 RCLCPP_ERROR(logger_,
"Error loading XML file: %s", default_bt_xml_filename_.c_str());
212 action_server_->activate();
216 template<
class ActionT>
219 action_server_->deactivate();
223 template<
class ActionT>
226 client_node_.reset();
227 action_server_.reset();
228 topic_logger_.reset();
229 plugin_lib_names_.clear();
230 current_bt_xml_filename_.clear();
232 bt_->haltAllActions(tree_);
233 bt_->resetGrootMonitor();
238 template<
class ActionT>
241 enable_groot_monitoring_ = enable;
242 groot_server_port_ = server_port;
245 template<
class ActionT>
249 auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename;
252 if (!always_reload_bt_xml_ && current_bt_xml_filename_ == filename) {
253 RCLCPP_DEBUG(logger_,
"BT will not be reloaded as the given xml is already loaded");
258 bt_->resetGrootMonitor();
261 std::ifstream xml_file(filename);
263 if (!xml_file.good()) {
264 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
265 "Couldn't open input XML file: " + filename);
271 tree_ = bt_->createTreeFromFile(filename, blackboard_);
272 for (
auto & subtree : tree_.subtrees) {
273 auto & blackboard = subtree->blackboard;
274 blackboard->set(
"node", client_node_);
275 blackboard->set<std::chrono::milliseconds>(
"server_timeout", default_server_timeout_);
276 blackboard->set<std::chrono::milliseconds>(
"bt_loop_duration", bt_loop_duration_);
277 blackboard->set<std::chrono::milliseconds>(
278 "wait_for_service_timeout",
279 wait_for_service_timeout_);
281 }
catch (
const std::exception & e) {
282 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
283 std::string(
"Exception when loading BT: ") + e.what());
287 topic_logger_ = std::make_unique<RosTopicLogger>(client_node_, tree_);
289 current_bt_xml_filename_ = filename;
292 if (enable_groot_monitoring_) {
293 bt_->addGrootMonitoring(&tree_, groot_server_port_);
295 logger_,
"Enabling Groot2 monitoring for %s: %d",
296 action_name_.c_str(), groot_server_port_);
302 template<
class ActionT>
305 if (!on_goal_received_callback_(action_server_->get_current_goal())) {
308 auto result = std::make_shared<typename ActionT::Result>();
309 populateErrorCode(result);
310 action_server_->terminate_current(result);
315 auto is_canceling = [&]() {
316 if (action_server_ ==
nullptr) {
317 RCLCPP_DEBUG(logger_,
"Action server unavailable. Canceling.");
320 if (!action_server_->is_server_active()) {
321 RCLCPP_DEBUG(logger_,
"Action server is inactive. Canceling.");
324 return action_server_->is_cancel_requested();
327 auto on_loop = [&]() {
328 if (action_server_->is_preempt_requested() && on_preempt_callback_) {
329 on_preempt_callback_(action_server_->get_pending_goal());
331 topic_logger_->flush();
336 nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling, bt_loop_duration_);
340 bt_->haltAllActions(tree_);
344 auto result = std::make_shared<typename ActionT::Result>();
346 populateErrorCode(result);
348 on_completion_callback_(result, rc);
351 case nav2_behavior_tree::BtStatus::SUCCEEDED:
352 action_server_->succeeded_current(result);
353 RCLCPP_INFO(logger_,
"Goal succeeded");
356 case nav2_behavior_tree::BtStatus::FAILED:
357 action_server_->terminate_current(result);
358 RCLCPP_ERROR(logger_,
"Goal failed error_code:%d error_msg:'%s'", result->error_code,
359 result->error_msg.c_str());
362 case nav2_behavior_tree::BtStatus::CANCELED:
363 action_server_->terminate_all(result);
364 RCLCPP_INFO(logger_,
"Goal canceled");
371 template<
class ActionT>
374 internal_error_code_ = error_code;
375 internal_error_msg_ = error_msg;
376 RCLCPP_ERROR(logger_,
"Setting internal error error_code:%d, error_msg:%s",
377 internal_error_code_, internal_error_msg_.c_str());
380 template<
class ActionT>
383 internal_error_code_ = ActionT::Result::NONE;
384 internal_error_msg_ =
"";
387 template<
class ActionT>
389 typename std::shared_ptr<typename ActionT::Result> result)
391 if (internal_error_code_ != ActionT::Result::NONE) {
392 result->error_code = internal_error_code_;
393 result->error_msg = internal_error_msg_;
399 template<
class ActionT>
401 typename std::shared_ptr<typename ActionT::Result> result)
403 int highest_priority_error_code = std::numeric_limits<int>::max();
404 std::string highest_priority_error_msg =
"";
407 if (internal_error_code_ != 0) {
408 highest_priority_error_code = internal_error_code_;
409 highest_priority_error_msg = internal_error_msg_;
412 for (
const auto & error_code_name_prefix : error_code_name_prefixes_) {
414 name = error_code_name_prefix +
"_error_code";
415 int current_error_code = blackboard_->get<
int>(name);
416 if (current_error_code != 0 && current_error_code < highest_priority_error_code) {
417 highest_priority_error_code = current_error_code;
418 name = error_code_name_prefix +
"_error_msg";
419 highest_priority_error_msg = blackboard_->get<std::string>(name);
424 "Failed to get error code name: %s from blackboard",
429 if (highest_priority_error_code != std::numeric_limits<int>::max()) {
430 result->error_code = highest_priority_error_code;
431 result->error_msg = highest_priority_error_msg;
435 template<
class ActionT>
439 for (
const auto & error_code_name_prefix : error_code_name_prefixes_) {
440 name = error_code_name_prefix +
"_error_code";
441 blackboard_->set<
unsigned short>(name, 0);
442 name = error_code_name_prefix +
"_error_msg";
443 blackboard_->set<std::string>(name,
"");
445 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.
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
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.
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,...