Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
bt_service_node.hpp
1 // Copyright (c) 2019 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_BEHAVIOR_TREE__BT_SERVICE_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_SERVICE_NODE_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <chrono>
21 
22 #include "behaviortree_cpp/action_node.h"
23 #include "behaviortree_cpp/json_export.h"
24 #include "nav2_ros_common/node_utils.hpp"
25 #include "nav2_ros_common/lifecycle_node.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 #include "nav2_ros_common/service_client.hpp"
29 
30 namespace nav2_behavior_tree
31 {
32 
33 using namespace std::chrono_literals; // NOLINT
34 
41 template<class ServiceT>
42 class BtServiceNode : public BT::ActionNodeBase
43 {
44 public:
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_(
56  service_node_name)
57  {
58  initialize();
59 
60  // Make a request for the service without parameter
61  request_ = std::make_shared<typename ServiceT::Request>();
62 
63  // Make sure the server is actually there before continuing
64  RCLCPP_DEBUG(
65  node_->get_logger(), "Waiting for \"%s\" service",
66  service_name_.c_str());
67  if (!service_client_->wait_for_service(wait_for_service_timeout_)) {
68  RCLCPP_ERROR(
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(
73  "Service server %s not available",
74  service_name_.c_str()));
75  }
76 
77  RCLCPP_DEBUG(
78  node_->get_logger(), "\"%s\" BtServiceNode initialized",
79  service_node_name_.c_str());
80  }
81 
82  BtServiceNode() = delete;
83 
84  virtual ~BtServiceNode()
85  {
86  }
87 
91  void initialize()
92  {
93  // Get the required items from the blackboard
94  auto bt_loop_duration =
95  config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
96  getInputOrBlackboard("server_timeout", server_timeout_);
97  wait_for_service_timeout_ =
98  config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");
99 
100  // timeout should be less than bt_loop_duration to be able to finish the current tick
101  max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
102 
103  // Now that we have node_ to use, create the service client for this BT service
104  createROSInterfaces();
105  }
106 
111  {
112  std::string service_new;
113  getInput("service_name", service_new);
114  if (service_new != service_name_ || !service_client_) {
115  service_name_ = service_new;
116  node_ = config().blackboard->template get<nav2::LifecycleNode::SharedPtr>("node");
117  service_client_ =
118  node_->create_client<ServiceT>(
119  service_name_, true /*creates and spins an internal executor*/);
120  }
121  }
122 
129  static BT::PortsList providedBasicPorts(BT::PortsList addition)
130  {
131  BT::PortsList basic = {
132  BT::InputPort<std::string>("service_name", "please_set_service_name_in_BT_Node"),
133  BT::InputPort<std::chrono::milliseconds>("server_timeout")
134  };
135  basic.insert(addition.begin(), addition.end());
136 
137  return basic;
138  }
139 
144  static BT::PortsList providedPorts()
145  {
146  return providedBasicPorts({});
147  }
148 
153  BT::NodeStatus tick() override
154  {
155  if (!BT::isStatusActive(status())) {
156  initialize();
157  }
158 
159  if (!request_sent_) {
160  // reset the flag to send the request or not,
161  // allowing the user the option to set it in on_tick
162  should_send_request_ = true;
163 
164  // Clear the input request to make sure we have no leftover from previous calls
165  request_ = std::make_shared<typename ServiceT::Request>();
166 
167  // user defined callback, may modify "should_send_request_".
168  on_tick();
169 
170  if (!should_send_request_) {
171  return BT::NodeStatus::FAILURE;
172  }
173 
174  future_result_ = service_client_->async_call(request_);
175  sent_time_ = node_->now();
176  request_sent_ = true;
177  }
178  return check_future();
179  }
180 
184  void halt() override
185  {
186  request_sent_ = false;
187  resetStatus();
188  }
189 
194  virtual void on_tick()
195  {
196  }
197 
204  virtual BT::NodeStatus on_completion(std::shared_ptr<typename ServiceT::Response>/*response*/)
205  {
206  return BT::NodeStatus::SUCCESS;
207  }
208 
213  virtual BT::NodeStatus check_future()
214  {
215  auto elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
216  auto remaining = server_timeout_ - elapsed;
217 
218  if (remaining > std::chrono::milliseconds(0)) {
219  auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
220 
221  rclcpp::FutureReturnCode rc;
222  rc = service_client_->spin_until_complete(future_result_, timeout);
223  if (rc == rclcpp::FutureReturnCode::SUCCESS) {
224  request_sent_ = false;
225  BT::NodeStatus status = on_completion(future_result_.get());
226  return status;
227  }
228 
229  if (rc == rclcpp::FutureReturnCode::TIMEOUT) {
230  on_wait_for_result();
231  elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
232  if (elapsed < server_timeout_) {
233  return BT::NodeStatus::RUNNING;
234  }
235  }
236  }
237 
238  RCLCPP_WARN(
239  node_->get_logger(),
240  "Node timed out while executing service call to %s.", service_name_.c_str());
241  request_sent_ = false;
242  return BT::NodeStatus::FAILURE;
243  }
244 
249  virtual void on_wait_for_result()
250  {
251  }
252 
253 protected:
258  {
259  int recovery_count = 0;
260  [[maybe_unused]] auto res = config().blackboard->get("number_recoveries", recovery_count); // NOLINT
261  recovery_count += 1;
262  config().blackboard->set("number_recoveries", recovery_count); // NOLINT
263  }
264 
265  std::string service_name_, service_node_name_;
266  typename nav2::ServiceClient<ServiceT>::SharedPtr service_client_;
267  std::shared_ptr<typename ServiceT::Request> request_;
268 
269  // The node that will be used for any ROS operations
270  nav2::LifecycleNode::SharedPtr node_;
271 
272  // The timeout value while to use in the tick loop while waiting for
273  // a result from the server
274  std::chrono::milliseconds server_timeout_;
275 
276  // The timeout value for BT loop execution
277  std::chrono::milliseconds max_timeout_;
278 
279  // The timeout value for waiting for a service to response
280  std::chrono::milliseconds wait_for_service_timeout_;
281 
282  // To track the server response when a new request is sent
283  std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
284  bool request_sent_{false};
285  rclcpp::Time sent_time_;
286 
287  // Can be set in on_tick or on_wait_for_result to indicate if a request should be sent.
288  bool should_send_request_;
289 };
290 
291 } // namespace nav2_behavior_tree
292 
293 #endif // NAV2_BEHAVIOR_TREE__BT_SERVICE_NODE_HPP_
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....