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_ros_common/node_utils.hpp"
30 #include "rcl_action/action_server.h"
31 #include "nav2_ros_common/lifecycle_node.hpp"
33 namespace nav2_behavior_tree
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),
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,
class NodeT>
128 template<
class ActionT,
class NodeT>
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(),
'/',
'_');
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);
148 client_node_ = std::make_shared<nav2::LifecycleNode>(
"_", options);
149 client_node_->configure();
150 client_node_->activate();
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_);
165 action_server_ = nav2::interfaces::create_action_server<ActionT>(
167 nullptr, std::chrono::milliseconds(500),
false);
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_);
182 error_code_name_prefixes_ = node->get_parameter(
"error_code_name_prefixes").as_string_array();
185 bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_, client_node_);
188 blackboard_ = BT::Blackboard::create();
191 blackboard_->set<nav2::LifecycleNode::SharedPtr>(
"node", client_node_);
192 blackboard_->set<std::chrono::milliseconds>(
"server_timeout", default_server_timeout_);
193 blackboard_->set<std::chrono::milliseconds>(
"bt_loop_duration", bt_loop_duration_);
194 blackboard_->set<std::chrono::milliseconds>(
195 "wait_for_service_timeout",
196 wait_for_service_timeout_);
201 template<
class ActionT,
class NodeT>
204 resetInternalError();
205 if (!loadBehaviorTree(default_bt_xml_filename_)) {
206 RCLCPP_ERROR(logger_,
"Error loading XML file: %s", default_bt_xml_filename_.c_str());
209 action_server_->activate();
213 template<
class ActionT,
class NodeT>
216 action_server_->deactivate();
220 template<
class ActionT,
class NodeT>
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();
231 bt_->haltAllActions(tree_);
232 bt_->resetGrootMonitor();
237 template<
class ActionT,
class NodeT>
240 const unsigned server_port)
242 enable_groot_monitoring_ = enable;
243 groot_server_port_ = server_port;
246 template<
class ActionT,
class NodeT>
250 auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename;
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");
259 bt_->resetGrootMonitor();
262 std::ifstream xml_file(filename);
264 if (!xml_file.good()) {
265 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
266 "Couldn't open input XML file: " + filename);
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_);
282 }
catch (
const std::exception & e) {
283 setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
284 std::string(
"Exception when loading BT: ") + e.what());
288 topic_logger_ = std::make_unique<RosTopicLogger>(client_node_, tree_);
290 current_bt_xml_filename_ = filename;
293 if (enable_groot_monitoring_) {
294 bt_->addGrootMonitoring(&tree_, groot_server_port_);
296 logger_,
"Enabling Groot2 monitoring for %s: %d",
297 action_name_.c_str(), groot_server_port_);
303 template<
class ActionT,
class NodeT>
306 if (!on_goal_received_callback_(action_server_->get_current_goal())) {
309 auto result = std::make_shared<typename ActionT::Result>();
310 populateErrorCode(result);
311 action_server_->terminate_current(result);
316 auto is_canceling = [&]() {
317 if (action_server_ ==
nullptr) {
318 RCLCPP_DEBUG(logger_,
"Action server unavailable. Canceling.");
321 if (!action_server_->is_server_active()) {
322 RCLCPP_DEBUG(logger_,
"Action server is inactive. Canceling.");
325 return action_server_->is_cancel_requested();
328 auto on_loop = [&]() {
329 if (action_server_->is_preempt_requested() && on_preempt_callback_) {
330 on_preempt_callback_(action_server_->get_pending_goal());
332 topic_logger_->flush();
337 nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling, bt_loop_duration_);
341 bt_->haltAllActions(tree_);
345 auto result = std::make_shared<typename ActionT::Result>();
347 populateErrorCode(result);
349 on_completion_callback_(result, rc);
352 case nav2_behavior_tree::BtStatus::SUCCEEDED:
353 action_server_->succeeded_current(result);
354 RCLCPP_INFO(logger_,
"Goal succeeded");
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());
363 case nav2_behavior_tree::BtStatus::CANCELED:
364 action_server_->terminate_all(result);
365 RCLCPP_INFO(logger_,
"Goal canceled");
372 template<
class ActionT,
class NodeT>
375 const std::string & error_msg)
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());
383 template<
class ActionT,
class NodeT>
386 internal_error_code_ = ActionT::Result::NONE;
387 internal_error_msg_ =
"";
390 template<
class ActionT,
class NodeT>
392 typename std::shared_ptr<typename ActionT::Result> result)
394 if (internal_error_code_ != ActionT::Result::NONE) {
395 result->error_code = internal_error_code_;
396 result->error_msg = internal_error_msg_;
402 template<
class ActionT,
class NodeT>
404 typename std::shared_ptr<typename ActionT::Result> result)
406 int highest_priority_error_code = std::numeric_limits<int>::max();
407 std::string highest_priority_error_msg =
"";
410 if (internal_error_code_ != 0) {
411 highest_priority_error_code = internal_error_code_;
412 highest_priority_error_msg = internal_error_msg_;
415 for (
const auto & error_code_name_prefix : error_code_name_prefixes_) {
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);
427 "Failed to get error code name: %s from blackboard",
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;
438 template<
class ActionT,
class NodeT>
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);
445 name = error_code_name_prefix +
"_error_msg";
446 blackboard_->set<std::string>(name,
"");
448 resetInternalError();
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.