15 #ifndef NAV2_BEHAVIOR_TREE__BT_SERVICE_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_SERVICE_NODE_HPP_
22 #include "behaviortree_cpp/action_node.h"
23 #include "nav2_util/node_utils.hpp"
24 #include "rclcpp/rclcpp.hpp"
25 #include "nav2_behavior_tree/bt_utils.hpp"
27 namespace nav2_behavior_tree
30 using namespace std::chrono_literals;
36 template<
class ServiceT>
47 const std::string & service_node_name,
48 const BT::NodeConfiguration & conf,
49 const std::string & service_name =
"")
50 : BT::ActionNodeBase(service_node_name, conf), service_name_(service_name), service_node_name_(
53 node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>(
"node");
54 callback_group_ = node_->create_callback_group(
55 rclcpp::CallbackGroupType::MutuallyExclusive,
57 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
60 auto bt_loop_duration =
61 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
62 getInputOrBlackboard(
"server_timeout", server_timeout_);
63 wait_for_service_timeout_ =
64 config().blackboard->template get<std::chrono::milliseconds>(
"wait_for_service_timeout");
67 max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
70 getInput(
"service_name", service_name_);
71 service_client_ = node_->create_client<ServiceT>(
73 rclcpp::SystemDefaultsQoS(),
77 request_ = std::make_shared<typename ServiceT::Request>();
81 node_->get_logger(),
"Waiting for \"%s\" service",
82 service_name_.c_str());
83 if (!service_client_->wait_for_service(wait_for_service_timeout_)) {
85 node_->get_logger(),
"\"%s\" service server not available after waiting for %.2fs",
86 service_name_.c_str(), wait_for_service_timeout_.count() / 1000.0);
87 throw std::runtime_error(
89 "Service server %s not available",
90 service_name_.c_str()));
94 node_->get_logger(),
"\"%s\" BtServiceNode initialized",
95 service_node_name_.c_str());
112 BT::PortsList basic = {
113 BT::InputPort<std::string>(
"service_name",
"please_set_service_name_in_BT_Node"),
114 BT::InputPort<std::chrono::milliseconds>(
"server_timeout")
116 basic.insert(addition.begin(), addition.end());
127 return providedBasicPorts({});
136 if (!request_sent_) {
139 should_send_request_ =
true;
142 request_ = std::make_shared<typename ServiceT::Request>();
147 if (!should_send_request_) {
148 return BT::NodeStatus::FAILURE;
151 future_result_ = service_client_->async_send_request(request_).share();
152 sent_time_ = node_->now();
153 request_sent_ =
true;
155 return check_future();
163 request_sent_ =
false;
181 virtual BT::NodeStatus
on_completion(std::shared_ptr<typename ServiceT::Response>)
183 return BT::NodeStatus::SUCCESS;
192 auto elapsed = (node_->now() - sent_time_).
template to_chrono<std::chrono::milliseconds>();
193 auto remaining = server_timeout_ - elapsed;
195 if (remaining > std::chrono::milliseconds(0)) {
196 auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
198 rclcpp::FutureReturnCode rc;
199 rc = callback_group_executor_.spin_until_future_complete(future_result_, timeout);
200 if (rc == rclcpp::FutureReturnCode::SUCCESS) {
201 request_sent_ =
false;
202 BT::NodeStatus status = on_completion(future_result_.get());
206 if (rc == rclcpp::FutureReturnCode::TIMEOUT) {
207 on_wait_for_result();
208 elapsed = (node_->now() - sent_time_).
template to_chrono<std::chrono::milliseconds>();
209 if (elapsed < server_timeout_) {
210 return BT::NodeStatus::RUNNING;
217 "Node timed out while executing service call to %s.", service_name_.c_str());
218 request_sent_ =
false;
219 return BT::NodeStatus::FAILURE;
236 int recovery_count = 0;
237 [[maybe_unused]]
auto res = config().blackboard->get(
"number_recoveries", recovery_count);
239 config().blackboard->set(
"number_recoveries", recovery_count);
242 std::string service_name_, service_node_name_;
243 typename std::shared_ptr<rclcpp::Client<ServiceT>> service_client_;
244 std::shared_ptr<typename ServiceT::Request> request_;
247 rclcpp::Node::SharedPtr node_;
248 rclcpp::CallbackGroup::SharedPtr callback_group_;
249 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
253 std::chrono::milliseconds server_timeout_;
256 std::chrono::milliseconds max_timeout_;
259 std::chrono::milliseconds wait_for_service_timeout_;
262 std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
263 bool request_sent_{
false};
264 rclcpp::Time sent_time_;
267 bool should_send_request_;
Abstract class representing a service based BT node.
BT::NodeStatus tick() override
The main override required by a BT service.
virtual void on_tick()
Function to perform some user-defined operation on tick Fill in service request with information if n...
static BT::PortsList providedPorts()
Creates list of BT ports.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtServiceNode that accepts parameters must provide a providedPorts method and call pr...
virtual BT::NodeStatus check_future()
Check the future and decide the status of BT.
void halt() override
The other (optional) override required by a BT service.
void increment_recovery_count()
Function to increment recovery count on blackboard if this node wraps a recovery.
virtual void on_wait_for_result()
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been...
BtServiceNode(const std::string &service_node_name, const BT::NodeConfiguration &conf, const std::string &service_name="")
A nav2_behavior_tree::BtServiceNode constructor.
virtual BT::NodeStatus on_completion(std::shared_ptr< typename ServiceT::Response >)
Function to perform some user-defined operation upon successful completion of the service....