15 #ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_
22 #include "behaviortree_cpp_v3/action_node.h"
23 #include "nav2_util/node_utils.hpp"
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "nav2_behavior_tree/bt_conversions.hpp"
27 namespace nav2_behavior_tree
30 using namespace std::chrono_literals;
36 template<
class ActionT>
47 const std::string & xml_tag_name,
48 const std::string & action_name,
49 const BT::NodeConfiguration & conf)
50 : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name), should_send_goal_(true)
52 node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>(
"node");
53 callback_group_ = node_->create_callback_group(
54 rclcpp::CallbackGroupType::MutuallyExclusive,
56 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
59 auto bt_loop_duration =
60 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
62 config().blackboard->template get<std::chrono::milliseconds>(
"server_timeout");
63 getInput<std::chrono::milliseconds>(
"server_timeout", server_timeout_);
64 wait_for_service_timeout_ =
65 config().blackboard->template get<std::chrono::milliseconds>(
"wait_for_service_timeout");
68 max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
71 goal_ =
typename ActionT::Goal();
72 result_ =
typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult();
74 std::string remapped_action_name;
75 if (getInput(
"server_name", remapped_action_name)) {
76 action_name_ = remapped_action_name;
78 createActionClient(action_name_);
81 RCLCPP_DEBUG(node_->get_logger(),
"\"%s\" BtActionNode initialized", xml_tag_name.c_str());
97 action_client_ = rclcpp_action::create_client<ActionT>(node_, action_name, callback_group_);
100 RCLCPP_DEBUG(node_->get_logger(),
"Waiting for \"%s\" action server", action_name.c_str());
101 if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
103 node_->get_logger(),
"\"%s\" action server not available after waiting for %.2fs",
105 wait_for_service_timeout_.count() / 1000.0);
106 throw std::runtime_error(
107 std::string(
"Action server ") + action_name +
108 std::string(
" not available"));
120 BT::PortsList basic = {
121 BT::InputPort<std::string>(
"server_name",
"Action server name"),
122 BT::InputPort<std::chrono::milliseconds>(
"server_timeout")
124 basic.insert(addition.begin(), addition.end());
135 return providedBasicPorts({});
167 return BT::NodeStatus::SUCCESS;
176 return BT::NodeStatus::FAILURE;
185 return BT::NodeStatus::SUCCESS;
195 if (status() == BT::NodeStatus::IDLE) {
197 setStatus(BT::NodeStatus::RUNNING);
200 should_send_goal_ =
true;
205 if (!should_send_goal_) {
206 return BT::NodeStatus::FAILURE;
214 if (future_goal_handle_) {
216 (node_->now() - time_goal_sent_).
template to_chrono<std::chrono::milliseconds>();
217 if (!is_future_goal_handle_complete(elapsed)) {
219 if (elapsed < server_timeout_) {
220 return BT::NodeStatus::RUNNING;
225 "Timed out while waiting for action server to acknowledge goal request for %s",
226 action_name_.c_str());
227 future_goal_handle_.reset();
228 return BT::NodeStatus::FAILURE;
233 if (rclcpp::ok() && !goal_result_available_) {
235 on_wait_for_result(feedback_);
240 auto goal_status = goal_handle_->get_status();
241 if (goal_updated_ && (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING ||
242 goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED))
244 goal_updated_ =
false;
247 (node_->now() - time_goal_sent_).
template to_chrono<std::chrono::milliseconds>();
248 if (!is_future_goal_handle_complete(elapsed)) {
249 if (elapsed < server_timeout_) {
250 return BT::NodeStatus::RUNNING;
254 "Timed out while waiting for action server to acknowledge goal request for %s",
255 action_name_.c_str());
256 future_goal_handle_.reset();
257 return BT::NodeStatus::FAILURE;
261 callback_group_executor_.spin_some();
264 if (!goal_result_available_) {
266 return BT::NodeStatus::RUNNING;
269 }
catch (
const std::runtime_error & e) {
270 if (e.what() == std::string(
"send_goal failed") ||
271 e.what() == std::string(
"Goal was rejected by the action server"))
274 return BT::NodeStatus::FAILURE;
281 BT::NodeStatus status;
282 switch (result_.code) {
283 case rclcpp_action::ResultCode::SUCCEEDED:
284 status = on_success();
287 case rclcpp_action::ResultCode::ABORTED:
288 status = on_aborted();
291 case rclcpp_action::ResultCode::CANCELED:
292 status = on_cancelled();
296 throw std::logic_error(
"BtActionNode::Tick: invalid status value");
299 goal_handle_.reset();
309 if (should_cancel_goal()) {
310 auto future_result = action_client_->async_get_result(goal_handle_);
311 auto future_cancel = action_client_->async_cancel_goal(goal_handle_);
312 if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
313 rclcpp::FutureReturnCode::SUCCESS)
317 "Failed to cancel action server for %s", action_name_.c_str());
320 if (callback_group_executor_.spin_until_future_complete(future_result, server_timeout_) !=
321 rclcpp::FutureReturnCode::SUCCESS)
325 "Failed to get result for %s in node halt!", action_name_.c_str());
331 setStatus(BT::NodeStatus::IDLE);
342 if (status() != BT::NodeStatus::RUNNING) {
351 callback_group_executor_.spin_some();
352 auto status = goal_handle_->get_status();
355 return status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED ||
356 status == action_msgs::msg::GoalStatus::STATUS_EXECUTING;
364 goal_result_available_ =
false;
365 auto send_goal_options =
typename rclcpp_action::Client<ActionT>::SendGoalOptions();
366 send_goal_options.result_callback =
367 [
this](
const typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult & result) {
368 if (future_goal_handle_) {
371 "Goal result for %s available, but it hasn't received the goal response yet. "
372 "It's probably a goal result for the last goal request", action_name_.c_str());
379 if (this->goal_handle_->get_goal_id() == result.goal_id) {
380 goal_result_available_ =
true;
384 send_goal_options.feedback_callback =
385 [
this](
typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr,
386 const std::shared_ptr<const typename ActionT::Feedback> feedback) {
387 feedback_ = feedback;
390 future_goal_handle_ = std::make_shared<
391 std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>(
392 action_client_->async_send_goal(goal_, send_goal_options));
393 time_goal_sent_ = node_->now();
404 auto remaining = server_timeout_ - elapsed;
407 if (remaining <= std::chrono::milliseconds(0)) {
408 future_goal_handle_.reset();
412 auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
414 callback_group_executor_.spin_until_future_complete(*future_goal_handle_, timeout);
417 if (result == rclcpp::FutureReturnCode::INTERRUPTED) {
418 future_goal_handle_.reset();
419 throw std::runtime_error(
"send_goal failed");
422 if (result == rclcpp::FutureReturnCode::SUCCESS) {
423 goal_handle_ = future_goal_handle_->get();
424 future_goal_handle_.reset();
426 throw std::runtime_error(
"Goal was rejected by the action server");
439 int recovery_count = 0;
440 config().blackboard->template get<int>(
"number_recoveries", recovery_count);
442 config().blackboard->template set<int>(
"number_recoveries", recovery_count);
445 std::string action_name_;
446 typename std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_;
449 typename ActionT::Goal goal_;
450 bool goal_updated_{
false};
451 bool goal_result_available_{
false};
452 typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr goal_handle_;
453 typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult result_;
456 std::shared_ptr<const typename ActionT::Feedback> feedback_;
459 rclcpp::Node::SharedPtr node_;
460 rclcpp::CallbackGroup::SharedPtr callback_group_;
461 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
465 std::chrono::milliseconds server_timeout_;
468 std::chrono::milliseconds max_timeout_;
471 std::chrono::milliseconds wait_for_service_timeout_;
474 std::shared_ptr<std::shared_future<typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr>>
476 rclcpp::Time time_goal_sent_;
479 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 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.