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(
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<rclcpp::Node::SharedPtr>("node");
117  service_client_ = std::make_shared<nav2_util::ServiceClient<ServiceT>>(
118  service_name_, node_, true /*creates and spins an internal executor*/);
119  }
120  }
121 
128  static BT::PortsList providedBasicPorts(BT::PortsList addition)
129  {
130  BT::PortsList basic = {
131  BT::InputPort<std::string>("service_name", "please_set_service_name_in_BT_Node"),
132  BT::InputPort<std::chrono::milliseconds>("server_timeout")
133  };
134  basic.insert(addition.begin(), addition.end());
135 
136  return basic;
137  }
138 
143  static BT::PortsList providedPorts()
144  {
145  return providedBasicPorts({});
146  }
147 
152  BT::NodeStatus tick() override
153  {
154  if (!BT::isStatusActive(status())) {
155  initialize();
156  }
157 
158  if (!request_sent_) {
159  // reset the flag to send the request or not,
160  // allowing the user the option to set it in on_tick
161  should_send_request_ = true;
162 
163  // Clear the input request to make sure we have no leftover from previous calls
164  request_ = std::make_shared<typename ServiceT::Request>();
165 
166  // user defined callback, may modify "should_send_request_".
167  on_tick();
168 
169  if (!should_send_request_) {
170  return BT::NodeStatus::FAILURE;
171  }
172 
173  future_result_ = service_client_->async_call(request_);
174  sent_time_ = node_->now();
175  request_sent_ = true;
176  }
177  return check_future();
178  }
179 
183  void halt() override
184  {
185  request_sent_ = false;
186  resetStatus();
187  }
188 
193  virtual void on_tick()
194  {
195  }
196 
203  virtual BT::NodeStatus on_completion(std::shared_ptr<typename ServiceT::Response>/*response*/)
204  {
205  return BT::NodeStatus::SUCCESS;
206  }
207 
212  virtual BT::NodeStatus check_future()
213  {
214  auto elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
215  auto remaining = server_timeout_ - elapsed;
216 
217  if (remaining > std::chrono::milliseconds(0)) {
218  auto timeout = remaining > max_timeout_ ? max_timeout_ : remaining;
219 
220  rclcpp::FutureReturnCode rc;
221  rc = service_client_->spin_until_complete(future_result_, timeout);
222  if (rc == rclcpp::FutureReturnCode::SUCCESS) {
223  request_sent_ = false;
224  BT::NodeStatus status = on_completion(future_result_.get());
225  return status;
226  }
227 
228  if (rc == rclcpp::FutureReturnCode::TIMEOUT) {
229  on_wait_for_result();
230  elapsed = (node_->now() - sent_time_).template to_chrono<std::chrono::milliseconds>();
231  if (elapsed < server_timeout_) {
232  return BT::NodeStatus::RUNNING;
233  }
234  }
235  }
236 
237  RCLCPP_WARN(
238  node_->get_logger(),
239  "Node timed out while executing service call to %s.", service_name_.c_str());
240  request_sent_ = false;
241  return BT::NodeStatus::FAILURE;
242  }
243 
248  virtual void on_wait_for_result()
249  {
250  }
251 
252 protected:
257  {
258  int recovery_count = 0;
259  [[maybe_unused]] auto res = config().blackboard->get("number_recoveries", recovery_count); // NOLINT
260  recovery_count += 1;
261  config().blackboard->set("number_recoveries", recovery_count); // NOLINT
262  }
263 
264  std::string service_name_, service_node_name_;
265  typename nav2_util::ServiceClient<ServiceT>::SharedPtr service_client_;
266  std::shared_ptr<typename ServiceT::Request> request_;
267 
268  // The node that will be used for any ROS operations
269  rclcpp::Node::SharedPtr node_;
270 
271  // The timeout value while to use in the tick loop while waiting for
272  // a result from the server
273  std::chrono::milliseconds server_timeout_;
274 
275  // The timeout value for BT loop execution
276  std::chrono::milliseconds max_timeout_;
277 
278  // The timeout value for waiting for a service to response
279  std::chrono::milliseconds wait_for_service_timeout_;
280 
281  // To track the server response when a new request is sent
282  std::shared_future<typename ServiceT::Response::SharedPtr> future_result_;
283  bool request_sent_{false};
284  rclcpp::Time sent_time_;
285 
286  // Can be set in on_tick or on_wait_for_result to indicate if a request should be sent.
287  bool should_send_request_;
288 };
289 
290 } // namespace nav2_behavior_tree
291 
292 #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....