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 "behaviortree_cpp/json_export.h"
24 #include "nav2_util/node_utils.hpp"
25 #include "rclcpp/rclcpp.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 #include "nav2_util/service_client.hpp"
30 namespace nav2_behavior_tree
33 using namespace std::chrono_literals;
41 template<
class ServiceT>
52 const std::string & service_node_name,
53 const BT::NodeConfiguration & conf,
54 const std::string & service_name =
"")
55 : BT::ActionNodeBase(service_node_name, conf), service_name_(service_name), service_node_name_(
61 request_ = std::make_shared<typename ServiceT::Request>();
65 node_->get_logger(),
"Waiting for \"%s\" service",
66 service_name_.c_str());
67 if (!service_client_->wait_for_service(wait_for_service_timeout_)) {
69 node_->get_logger(),
"\"%s\" service server not available after waiting for %.2fs",
70 service_name_.c_str(), wait_for_service_timeout_.count() / 1000.0);
71 throw std::runtime_error(
72 std::string(
"Service server ") + service_name_ +
73 std::string(
" not available"));
77 node_->get_logger(),
"\"%s\" BtServiceNode initialized",
78 service_node_name_.c_str());
93 auto bt_loop_duration =
94 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
95 getInputOrBlackboard(
"server_timeout", server_timeout_);
96 wait_for_service_timeout_ =
97 config().blackboard->template get<std::chrono::milliseconds>(
"wait_for_service_timeout");
100 max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
103 createROSInterfaces();
111 std::string service_new;
112 getInput(
"service_name", service_new);
113 if (service_new != service_name_ || !service_client_) {
114 service_name_ = service_new;
115 node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>(
"node");
116 service_client_ = std::make_shared<nav2_util::ServiceClient<ServiceT>>(
117 service_name_, node_,
true );
129 BT::PortsList basic = {
130 BT::InputPort<std::string>(
"service_name",
"please_set_service_name_in_BT_Node"),
131 BT::InputPort<std::chrono::milliseconds>(
"server_timeout")
133 basic.insert(addition.begin(), addition.end());
144 return providedBasicPorts({});
153 if (!BT::isStatusActive(status())) {
157 if (!request_sent_) {
160 should_send_request_ =
true;
163 request_ = std::make_shared<typename ServiceT::Request>();
168 if (!should_send_request_) {
169 return BT::NodeStatus::FAILURE;
172 future_result_ = service_client_->async_call(request_);
173 sent_time_ = node_->now();
174 request_sent_ =
true;
176 return check_future();
184 request_sent_ =
false;
202 virtual BT::NodeStatus
on_completion(std::shared_ptr<typename ServiceT::Response>)
204 return BT::NodeStatus::SUCCESS;
213 auto elapsed = (node_->now() - sent_time_).
template to_chrono<std::chrono::milliseconds>();
214 auto remaining = server_timeout_ - elapsed;
216 if (remaining > std::chrono::milliseconds(0)) {
217 auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
219 rclcpp::FutureReturnCode rc;
220 rc = service_client_->spin_until_complete(future_result_, timeout);
221 if (rc == rclcpp::FutureReturnCode::SUCCESS) {
222 request_sent_ =
false;
223 BT::NodeStatus status = on_completion(future_result_.get());
227 if (rc == rclcpp::FutureReturnCode::TIMEOUT) {
228 on_wait_for_result();
229 elapsed = (node_->now() - sent_time_).
template to_chrono<std::chrono::milliseconds>();
230 if (elapsed < server_timeout_) {
231 return BT::NodeStatus::RUNNING;
238 "Node timed out while executing service call to %s.", service_name_.c_str());
239 request_sent_ =
false;
240 return BT::NodeStatus::FAILURE;
257 int recovery_count = 0;
258 [[maybe_unused]]
auto res = config().blackboard->get(
"number_recoveries", recovery_count);
260 config().blackboard->set(
"number_recoveries", recovery_count);
263 std::string service_name_, service_node_name_;
264 typename nav2_util::ServiceClient<ServiceT>::SharedPtr service_client_;
265 std::shared_ptr<typename ServiceT::Request> request_;
268 rclcpp::Node::SharedPtr node_;
272 std::chrono::milliseconds server_timeout_;
275 std::chrono::milliseconds max_timeout_;
278 std::chrono::milliseconds wait_for_service_timeout_;
281 std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
282 bool request_sent_{
false};
283 rclcpp::Time sent_time_;
286 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.
void initialize()
Function to read parameters and initialize class variables.
void createROSInterfaces()
Function to create ROS interfaces.
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....