15 #ifndef NAV2_BEHAVIOR_TREE__BT_CANCEL_ACTION_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_CANCEL_ACTION_NODE_HPP_
22 #include "behaviortree_cpp/action_node.h"
23 #include "nav2_ros_common/lifecycle_node.hpp"
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "nav2_behavior_tree/bt_utils.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)
52 node_ = config().blackboard->template get<nav2::LifecycleNode::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 getInputOrBlackboard(
"server_timeout", server_timeout_);
60 wait_for_service_timeout_ =
61 config().blackboard->template get<std::chrono::milliseconds>(
"wait_for_service_timeout");
63 std::string remapped_action_name;
64 if (getInput(
"server_name", remapped_action_name)) {
65 action_name_ = remapped_action_name;
67 createActionClient(action_name_);
71 node_->get_logger(),
"\"%s\" BtCancelActionNode initialized",
72 xml_tag_name.c_str());
88 action_client_ = node_->create_action_client<ActionT>(action_name, callback_group_);
91 RCLCPP_DEBUG(node_->get_logger(),
"Waiting for \"%s\" action server", action_name.c_str());
92 if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
94 node_->get_logger(),
"\"%s\" action server not available after waiting for %.2fs",
95 action_name.c_str(), wait_for_service_timeout_.count() / 1000.0);
96 throw std::runtime_error(
97 std::string(
"Action server ") + action_name +
98 std::string(
" not available"));
110 BT::PortsList basic = {
111 BT::InputPort<std::string>(
"server_name",
"Action server name"),
112 BT::InputPort<std::chrono::milliseconds>(
"server_timeout")
114 basic.insert(addition.begin(), addition.end());
129 return providedBasicPorts({});
139 setStatus(BT::NodeStatus::RUNNING);
144 rclcpp::Time goal_expiry_time = node_->now() - std::chrono::milliseconds(10);
146 auto future_cancel = action_client_->async_cancel_goals_before(goal_expiry_time);
148 if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
149 rclcpp::FutureReturnCode::SUCCESS)
153 "Failed to cancel the action server for %s", action_name_.c_str());
154 return BT::NodeStatus::FAILURE;
156 return BT::NodeStatus::SUCCESS;
160 std::string action_name_;
161 typename nav2::ActionClient<ActionT>::SharedPtr action_client_;
164 nav2::LifecycleNode::SharedPtr node_;
165 rclcpp::CallbackGroup::SharedPtr callback_group_;
166 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
170 std::chrono::milliseconds server_timeout_;
172 std::chrono::milliseconds wait_for_service_timeout_;
Abstract class representing an action for cancelling BT node.
void createActionClient(const std::string &action_name)
Create instance of an action client.
BtCancelActionNode(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::BtCancelActionNode constructor.
BT::NodeStatus tick() override
The main override required by a BT action.
static BT::PortsList providedPorts()
Creates list of BT ports.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtCancelActionNode that accepts parameters must provide a providedPorts method and ca...