Nav2 Navigation Stack - kilted  kilted
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_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"
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("Service server ") + service_name_ +
73  std::string(" not available"));
74  }
75 
76  RCLCPP_DEBUG(
77  node_->get_logger(), "\"%s\" BtServiceNode initialized",
78  service_node_name_.c_str());
79  }
80 
81  BtServiceNode() = delete;
82 
83  virtual ~BtServiceNode()
84  {
85  }
86 
90  void initialize()
91  {
92  // Get the required items from the blackboard
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");
98 
99  // timeout should be less than bt_loop_duration to be able to finish the current tick
100  max_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(bt_loop_duration * 0.5);
101 
102  // Now that we have node_ to use, create the service client for this BT service
103  createROSInterfaces();
104  }
105 
110  {
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 /*creates and spins an internal executor*/);
118  }
119  }
120 
127  static BT::PortsList providedBasicPorts(BT::PortsList addition)
128  {
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")
132  };
133  basic.insert(addition.begin(), addition.end());
134 
135  return basic;
136  }
137 
142  static BT::PortsList providedPorts()
143  {
144  return providedBasicPorts({});
145  }
146 
151  BT::NodeStatus tick() override
152  {
153  if (!BT::isStatusActive(status())) {
154  initialize();
155  }
156 
157  if (!request_sent_) {
158  // reset the flag to send the request or not,
159  // allowing the user the option to set it in on_tick
160  should_send_request_ = true;
161 
162  // Clear the input request to make sure we have no leftover from previous calls
163  request_ = std::make_shared<typename ServiceT::Request>();
164 
165  // user defined callback, may modify "should_send_request_".
166  on_tick();
167 
168  if (!should_send_request_) {
169  return BT::NodeStatus::FAILURE;
170  }
171 
172  future_result_ = service_client_->async_call(request_);
173  sent_time_ = node_->now();
174  request_sent_ = true;
175  }
176  return check_future();
177  }
178 
182  void halt() override
183  {
184  request_sent_ = false;
185  resetStatus();
186  }
187 
192  virtual void on_tick()
193  {
194  }
195 
202  virtual BT::NodeStatus on_completion(std::shared_ptr<typename ServiceT::Response>/*response*/)
203  {
204  return BT::NodeStatus::SUCCESS;
205  }
206 
211  virtual BT::NodeStatus check_future()
212  {
213  auto elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
214  auto remaining = server_timeout_ - elapsed;
215 
216  if (remaining > std::chrono::milliseconds(0)) {
217  auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
218 
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());
224  return status;
225  }
226 
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;
232  }
233  }
234  }
235 
236  RCLCPP_WARN(
237  node_->get_logger(),
238  "Node timed out while executing service call to %s.", service_name_.c_str());
239  request_sent_ = false;
240  return BT::NodeStatus::FAILURE;
241  }
242 
247  virtual void on_wait_for_result()
248  {
249  }
250 
251 protected:
256  {
257  int recovery_count = 0;
258  [[maybe_unused]] auto res = config().blackboard->get("number_recoveries", recovery_count); // NOLINT
259  recovery_count += 1;
260  config().blackboard->set("number_recoveries", recovery_count); // NOLINT
261  }
262 
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_;
266 
267  // The node that will be used for any ROS operations
268  rclcpp::Node::SharedPtr node_;
269 
270  // The timeout value while to use in the tick loop while waiting for
271  // a result from the server
272  std::chrono::milliseconds server_timeout_;
273 
274  // The timeout value for BT loop execution
275  std::chrono::milliseconds max_timeout_;
276 
277  // The timeout value for waiting for a service to response
278  std::chrono::milliseconds wait_for_service_timeout_;
279 
280  // To track the server response when a new request is sent
281  std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
282  bool request_sent_{false};
283  rclcpp::Time sent_time_;
284 
285  // Can be set in on_tick or on_wait_for_result to indicate if a request should be sent.
286  bool should_send_request_;
287 };
288 
289 } // namespace nav2_behavior_tree
290 
291 #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....