15 #ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
22 #include "behaviortree_cpp/action_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "nav2_ros_common/node_utils.hpp"
25 #include "rclcpp_action/rclcpp_action.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
29 namespace nav2_behavior_tree
32 using namespace std::chrono_literals;
40 template<
class ActionT>
51 const std::string & xml_tag_name,
52 const std::string & action_name,
53 const BT::NodeConfiguration & conf)
54 : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name), should_send_goal_(true)
56 node_ = config().blackboard->template get<nav2::LifecycleNode::SharedPtr>(
"node");
57 callback_group_ = node_->create_callback_group(
58 rclcpp::CallbackGroupType::MutuallyExclusive,
60 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
63 auto bt_loop_duration =
64 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
65 getInputOrBlackboard(
"server_timeout", server_timeout_);
66 wait_for_service_timeout_ =
67 config().blackboard->template get<std::chrono::milliseconds>(
"wait_for_service_timeout");
70 max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
73 goal_ =
typename ActionT::Goal();
74 result_ =
typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
76 std::string remapped_action_name;
77 if (getInput(
"server_name", remapped_action_name)) {
78 action_name_ = remapped_action_name;
80 createActionClient(action_name_);
83 RCLCPP_DEBUG(node_->get_logger(),
"\"%s\" BtActionNode initialized", xml_tag_name.c_str());
99 action_client_ = node_->create_action_client<ActionT>(action_name, callback_group_);
102 RCLCPP_DEBUG(node_->get_logger(),
"Waiting for \"%s\" action server", action_name.c_str());
103 if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
105 node_->get_logger(),
"\"%s\" action server not available after waiting for %.2fs",
107 wait_for_service_timeout_.count() / 1000.0);
108 throw std::runtime_error(
109 std::string(
"Action server ") + action_name +
110 std::string(
" not available"));
122 BT::PortsList basic = {
123 BT::InputPort<std::string>(
"server_name",
"Action server name"),
124 BT::InputPort<std::chrono::milliseconds>(
"server_timeout")
126 basic.insert(addition.begin(), addition.end());
137 return providedBasicPorts({});
169 return BT::NodeStatus::SUCCESS;
178 return BT::NodeStatus::FAILURE;
187 return BT::NodeStatus::SUCCESS;
206 if (!BT::isStatusActive(status())) {
208 should_send_goal_ =
true;
211 goal_ =
typename ActionT::Goal();
212 result_ =
typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
218 setStatus(BT::NodeStatus::RUNNING);
220 if (!should_send_goal_) {
221 return BT::NodeStatus::FAILURE;
229 if (future_goal_handle_) {
231 (node_->now() - time_goal_sent_).
template to_chrono<std::chrono::milliseconds>();
232 if (!is_future_goal_handle_complete(elapsed)) {
234 if (elapsed < server_timeout_) {
235 return BT::NodeStatus::RUNNING;
240 "Timed out while waiting for action server to acknowledge goal request for %s",
241 action_name_.c_str());
242 future_goal_handle_.reset();
244 return BT::NodeStatus::FAILURE;
249 if (rclcpp::ok() && !goal_result_available_) {
251 on_wait_for_result(feedback_);
256 auto goal_status = goal_handle_->get_status();
258 (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING ||
259 goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED))
261 goal_updated_ =
false;
264 (node_->now() - time_goal_sent_).
template to_chrono<std::chrono::milliseconds>();
265 if (!is_future_goal_handle_complete(elapsed)) {
266 if (elapsed < server_timeout_) {
267 return BT::NodeStatus::RUNNING;
271 "Timed out while waiting for action server to acknowledge goal request for %s",
272 action_name_.c_str());
273 future_goal_handle_.reset();
275 return BT::NodeStatus::FAILURE;
279 callback_group_executor_.spin_some();
282 if (!goal_result_available_) {
284 return BT::NodeStatus::RUNNING;
287 }
catch (
const std::runtime_error & e) {
288 if (e.what() == std::string(
"send_goal failed") ||
289 e.what() == std::string(
"Goal was rejected by the action server"))
292 return BT::NodeStatus::FAILURE;
299 BT::NodeStatus status;
300 switch (result_.code) {
301 case rclcpp_action::ResultCode::SUCCEEDED:
302 status = on_success();
305 case rclcpp_action::ResultCode::ABORTED:
306 status = on_aborted();
309 case rclcpp_action::ResultCode::CANCELED:
310 status = on_cancelled();
314 throw std::logic_error(
"BtActionNode::Tick: invalid status value");
317 goal_handle_.reset();
327 if (should_cancel_goal()) {
328 auto future_result = action_client_->async_get_result(goal_handle_);
329 auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
330 if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
331 rclcpp::FutureReturnCode::SUCCESS)
335 "Failed to cancel action server for %s", action_name_.c_str());
338 if (callback_group_executor_.spin_until_future_complete(future_result, server_timeout_) !=
339 rclcpp::FutureReturnCode::SUCCESS)
343 "Failed to get result for %s in node halt!", action_name_.c_str());
362 if (status() != BT::NodeStatus::RUNNING) {
371 callback_group_executor_.spin_some();
372 auto status = goal_handle_->get_status();
375 return status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
376 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING;
384 goal_result_available_ =
false;
385 auto send_goal_options =
typename nav2::ActionClient<ActionT>::SendGoalOptions();
386 send_goal_options.result_callback =
387 [
this](
const typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult & result) {
388 if (future_goal_handle_) {
391 "Goal result for %s available, but it hasn't received the goal response yet. "
392 "It's probably a goal result for the last goal request", action_name_.c_str());
399 if (this->goal_handle_->get_goal_id() == result.goal_id) {
400 goal_result_available_ =
true;
405 send_goal_options.feedback_callback =
406 [
this](
typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr,
407 const std::shared_ptr<const typename ActionT::Feedback> feedback) {
408 feedback_ = feedback;
412 future_goal_handle_ = std::make_shared<
413 std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>(
414 action_client_->async_send_goal(goal_, send_goal_options));
415 time_goal_sent_ = node_->now();
426 auto remaining = server_timeout_ - elapsed;
429 if (remaining <= std::chrono::milliseconds(0)) {
430 future_goal_handle_.reset();
434 auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
436 callback_group_executor_.spin_until_future_complete(*future_goal_handle_, timeout);
439 if (result == rclcpp::FutureReturnCode::INTERRUPTED) {
440 future_goal_handle_.reset();
441 throw std::runtime_error(
"send_goal failed");
444 if (result == rclcpp::FutureReturnCode::SUCCESS) {
445 goal_handle_ = future_goal_handle_->get();
446 future_goal_handle_.reset();
448 throw std::runtime_error(
"Goal was rejected by the action server");
461 int recovery_count = 0;
462 [[maybe_unused]]
auto res = config().blackboard->get(
"number_recoveries", recovery_count);
464 config().blackboard->set(
"number_recoveries", recovery_count);
467 std::string action_name_;
468 typename nav2::ActionClient<ActionT>::SharedPtr action_client_;
471 typename ActionT::Goal goal_;
472 bool goal_updated_{
false};
473 bool goal_result_available_{
false};
474 typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr goal_handle_;
475 typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult result_;
478 std::shared_ptr<const typename ActionT::Feedback> feedback_;
481 nav2::LifecycleNode::SharedPtr node_;
482 rclcpp::CallbackGroup::SharedPtr callback_group_;
483 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
487 std::chrono::milliseconds server_timeout_;
490 std::chrono::milliseconds max_timeout_;
493 std::chrono::milliseconds wait_for_service_timeout_;
496 std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>
498 rclcpp::Time time_goal_sent_;
501 bool should_send_goal_;
Abstract class representing an action based BT node.
BT::NodeStatus tick() override
The main override required by a BT action.
bool is_future_goal_handle_complete(std::chrono::milliseconds &elapsed)
Function to check if the action server acknowledged a new goal.
virtual BT::NodeStatus on_cancelled()
Function to perform some user-defined operation when the action is cancelled.
virtual BT::NodeStatus on_success()
Function to perform some user-defined operation upon successful completion of the action....
void halt() override
The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 ...
virtual void on_timeout()
Function to perform work in a BT Node when the action server times out Such as setting the error code...
virtual BT::NodeStatus on_aborted()
Function to perform some user-defined operation when the action is aborted.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call pro...
virtual void on_tick()
Function to perform some user-defined operation on tick Could do dynamic checks, such as getting upda...
void createActionClient(const std::string &action_name)
Create instance of an action client.
virtual void on_wait_for_result(std::shared_ptr< const typename ActionT::Feedback >)
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been...
void send_new_goal()
Function to send new goal to action server.
BtActionNode(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::BtActionNode constructor.
static BT::PortsList providedPorts()
Creates list of BT ports.
bool should_cancel_goal()
Function to check if current goal should be cancelled.
void increment_recovery_count()
Function to increment recovery count on blackboard if this node wraps a recovery.