AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
ros_service_node.hpp
1// Copyright 2024 Robin Müller
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// https://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#pragma once
16
17#include <chrono>
18#include <memory>
19#include <string>
20
21#include "auto_apms_behavior_tree_core/exceptions.hpp"
22#include "auto_apms_behavior_tree_core/node/ros_node_context.hpp"
23#include "auto_apms_util/string.hpp"
24#include "behaviortree_cpp/action_node.h"
25#include "rclcpp/executors.hpp"
26
28{
29
30enum ServiceNodeErrorCode
31{
32 SERVICE_UNREACHABLE,
33 SERVICE_TIMEOUT,
34 INVALID_REQUEST
35};
36
42inline const char * toStr(const ServiceNodeErrorCode & err)
43{
44 switch (err) {
45 case SERVICE_UNREACHABLE:
46 return "SERVICE_UNREACHABLE";
47 case SERVICE_TIMEOUT:
48 return "SERVICE_TIMEOUT";
49 case INVALID_REQUEST:
50 return "INVALID_REQUEST";
51 }
52 return nullptr;
53}
54
91template <class ServiceT>
92class RosServiceNode : public BT::ActionNodeBase
93{
94 using ServiceClient = typename rclcpp::Client<ServiceT>;
95 using ServiceClientPtr = std::shared_ptr<ServiceClient>;
96
97 struct ServiceClientInstance
98 {
99 ServiceClientInstance(
100 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group, const std::string & service_name);
101
102 ServiceClientPtr service_client;
103 std::string name;
104 };
105
106 using ClientsRegistry = std::unordered_map<std::string, std::weak_ptr<ServiceClientInstance>>;
107
108public:
109 using ServiceType = ServiceT;
110 using Request = typename ServiceT::Request;
111 using Response = typename ServiceT::Response;
112 using Config = BT::NodeConfig;
113 using Context = RosNodeContext;
114
124 explicit RosServiceNode(const std::string & instance_name, const Config & config, Context context);
125
126 virtual ~RosServiceNode() = default;
127
135 static BT::PortsList providedBasicPorts(BT::PortsList addition)
136 {
137 BT::PortsList basic = {BT::InputPort<std::string>("topic", "Name of the ROS 2 service.")};
138 basic.insert(addition.begin(), addition.end());
139 return basic;
140 }
141
146 static BT::PortsList providedPorts() { return providedBasicPorts({}); }
147
157 virtual bool setRequest(typename Request::SharedPtr & request);
158
168 virtual BT::NodeStatus onResponseReceived(const typename Response::SharedPtr & response);
169
179 virtual BT::NodeStatus onFailure(ServiceNodeErrorCode error);
180
186 bool createClient(const std::string & service_name);
187
192 std::string getServiceName() const;
193
194protected:
195 const Context context_;
196 const rclcpp::Logger logger_;
197
198 BT::NodeStatus tick() override final;
199
200 void halt() override final;
201
202private:
203 static std::mutex & getMutex();
204
205 static ClientsRegistry & getRegistry();
206
207 bool dynamic_client_instance_ = false;
208 std::shared_ptr<ServiceClientInstance> client_instance_;
209 typename ServiceClient::SharedFuture future_;
210 int64_t request_id_;
211 rclcpp::Time time_request_sent_;
212 BT::NodeStatus on_feedback_state_change_;
213 typename Response::SharedPtr response_;
214};
215
216// #####################################################################################################################
217// ################################ DEFINITIONS ##############################################
218// #####################################################################################################################
219
220template <class ServiceT>
221inline RosServiceNode<ServiceT>::ServiceClientInstance::ServiceClientInstance(
222 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group, const std::string & service_name)
223{
224 service_client = node->create_client<ServiceT>(service_name, rclcpp::ServicesQoS(), group);
225 name = service_name;
226}
227
228template <class ServiceT>
230 const std::string & instance_name, const Config & config, Context context)
231: BT::ActionNodeBase(instance_name, config),
232 context_(context),
233 logger_(context.getChildLogger(auto_apms_util::toSnakeCase(instance_name)))
234{
235 // Consider aliasing in ports and copy the values from aliased to original ports
236 this->modifyPortsRemapping(context_.copyAliasedPortValuesToOriginalPorts(this));
237
238 // Resolve topic field
239 if (const BT::Expected<std::string> expected_name = context_.getTopicName(this)) {
240 createClient(expected_name.value());
241 } else {
242 // We assume that determining the service name requires a blackboard pointer, which cannot be evaluated at
243 // construction time. The expression will be evaluated each time before the node is ticked the first time after
244 // successful execution.
245 dynamic_client_instance_ = true;
246 }
247}
248
249template <class ServiceT>
250inline BT::NodeStatus RosServiceNode<ServiceT>::tick()
251{
252 if (!rclcpp::ok()) {
253 halt();
254 return BT::NodeStatus::FAILURE;
255 }
256
257 // If client has been set up in derived constructor, event though this constructor couldn't, we discard the intention
258 // of dynamically creating the client
259 if (dynamic_client_instance_ && client_instance_) {
260 dynamic_client_instance_ = false;
261 }
262
263 // Try again to create the client on first tick if this was not possible during construction or if client should be
264 // created from a blackboard entry on the start of every iteration
265 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
266 const BT::Expected<std::string> expected_name = context_.getTopicName(this);
267 if (expected_name) {
268 createClient(expected_name.value());
269 } else {
270 throw exceptions::RosNodeError(
271 context_.getFullyQualifiedTreeNodeName(this) +
272 " - Cannot create the service client because the service name couldn't be resolved using "
273 "the expression specified by the node's registration parameters (" +
274 NodeRegistrationOptions::PARAM_NAME_ROS2TOPIC + ": " + context_.registration_options_.topic +
275 "). Error message: " + expected_name.error());
276 }
277 }
278
279 if (!client_instance_) {
280 throw exceptions::RosNodeError(context_.getFullyQualifiedTreeNodeName(this) + " - client_instance_ is nullptr.");
281 }
282
283 auto & service_client = client_instance_->service_client;
284
285 auto check_status = [this](BT::NodeStatus status) {
286 if (!isStatusCompleted(status)) {
287 throw exceptions::RosNodeError(
288 context_.getFullyQualifiedTreeNodeName(this) + " - The callback must return either SUCCESS or FAILURE.");
289 }
290 return status;
291 };
292
293 // first step to be done only at the beginning of the Action
294 if (status() == BT::NodeStatus::IDLE) {
295 setStatus(BT::NodeStatus::RUNNING);
296
297 on_feedback_state_change_ = BT::NodeStatus::RUNNING;
298 response_ = {};
299
300 typename Request::SharedPtr request = std::make_shared<Request>();
301
302 if (!setRequest(request)) {
303 return check_status(onFailure(INVALID_REQUEST));
304 }
305
306 // Check if server is ready
307 if (!service_client->service_is_ready()) {
308 return onFailure(SERVICE_UNREACHABLE);
309 }
310
311 const auto future_and_request_id =
312 service_client->async_send_request(request, [this](typename ServiceClient::SharedFuture response) {
313 if (response.wait_for(std::chrono::seconds(0)) != std::future_status::ready) {
314 throw exceptions::RosNodeError(
315 this->context_.getFullyQualifiedTreeNodeName(this) + " - Response not ready in response callback.");
316 }
317 this->response_ = response.get();
318 });
319 future_ = future_and_request_id.future;
320 request_id_ = future_and_request_id.request_id;
321 time_request_sent_ = context_.getCurrentTime();
322
323 RCLCPP_DEBUG(logger_, "%s - Service request sent.", context_.getFullyQualifiedTreeNodeName(this).c_str());
324 return BT::NodeStatus::RUNNING;
325 }
326
327 if (status() == BT::NodeStatus::RUNNING) {
328 // FIRST case: check if the goal request has a timeout
329 if (!response_) {
330 // See if we must time out
331 if ((context_.getCurrentTime() - time_request_sent_) > context_.registration_options_.request_timeout) {
332 // Remove the pending request with the client if timed out
333 client_instance_->service_client->remove_pending_request(request_id_);
334 return check_status(onFailure(SERVICE_TIMEOUT));
335 }
336 return BT::NodeStatus::RUNNING;
337 } else if (future_.valid()) {
338 // Invalidate future since it's obsolete now and it indicates that we've done this step
339 future_ = {};
340
341 RCLCPP_DEBUG(logger_, "%s - Service response received.", context_.getFullyQualifiedTreeNodeName(this).c_str());
342 }
343
344 // SECOND case: response received
345 return check_status(onResponseReceived(response_));
346 }
347 return BT::NodeStatus::RUNNING;
348}
349
350template <class ServiceT>
351inline void RosServiceNode<ServiceT>::halt()
352{
353 if (status() == BT::NodeStatus::RUNNING) {
354 resetStatus();
355 }
356}
357
358template <class ServiceT>
359inline bool RosServiceNode<ServiceT>::setRequest(typename Request::SharedPtr & /*request*/)
360{
361 return true;
362}
363
364template <class ServiceT>
365inline BT::NodeStatus RosServiceNode<ServiceT>::onResponseReceived(const typename Response::SharedPtr & /*response*/)
366{
367 return BT::NodeStatus::SUCCESS;
368}
369
370template <class ServiceT>
371inline BT::NodeStatus RosServiceNode<ServiceT>::onFailure(ServiceNodeErrorCode error)
372{
373 const std::string msg = context_.getFullyQualifiedTreeNodeName(this) + " - Unexpected error " +
374 std::to_string(error) + ": " + toStr(error) + ".";
375 RCLCPP_ERROR_STREAM(logger_, msg);
376 throw exceptions::RosNodeError(msg);
377}
378
379template <class ServiceT>
380inline bool RosServiceNode<ServiceT>::createClient(const std::string & service_name)
381{
382 if (service_name.empty()) {
383 throw exceptions::RosNodeError(
384 context_.getFullyQualifiedTreeNodeName(this) +
385 " - Argument service_name is empty when trying to create the client.");
386 }
387
388 // Check if the service with given name is already set up
389 if (
390 client_instance_ && service_name == client_instance_->name &&
391 client_instance_->service_client->service_is_ready()) {
392 return true;
393 }
394
395 std::unique_lock lk(getMutex());
396
397 rclcpp::Node::SharedPtr node = context_.nh_.lock();
398 if (!node) {
399 throw exceptions::RosNodeError(
400 context_.getFullyQualifiedTreeNodeName(this) +
401 " - The weak pointer to the ROS 2 node expired. The tree node doesn't "
402 "take ownership of it.");
403 }
404 rclcpp::CallbackGroup::SharedPtr group = context_.cb_group_.lock();
405 if (!group) {
406 throw exceptions::RosNodeError(
407 context_.getFullyQualifiedTreeNodeName(this) +
408 " - The weak pointer to the ROS 2 callback group expired. The tree node doesn't "
409 "take ownership of it.");
410 }
411 auto client_key = std::string(node->get_fully_qualified_name()) + "/" + service_name;
412
413 auto & registry = getRegistry();
414 auto it = registry.find(client_key);
415 if (it == registry.end() || it->second.expired()) {
416 client_instance_ = std::make_shared<ServiceClientInstance>(node, group, service_name);
417 registry.insert({client_key, client_instance_});
418 RCLCPP_DEBUG(
419 logger_, "%s - Created client for service '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
420 service_name.c_str());
421 } else {
422 client_instance_ = it->second.lock();
423 }
424
425 bool found = client_instance_->service_client->wait_for_service(context_.registration_options_.wait_timeout);
426 if (!found) {
427 std::string msg = context_.getFullyQualifiedTreeNodeName(this) + " - Service with name '" + client_instance_->name +
428 "' is not reachable.";
429 if (context_.registration_options_.allow_unreachable) {
430 RCLCPP_WARN_STREAM(logger_, msg);
431 } else {
432 RCLCPP_ERROR_STREAM(logger_, msg);
433 throw exceptions::RosNodeError(msg);
434 }
435 }
436 return found;
437}
438
439template <class ServiceT>
441{
442 if (client_instance_) return client_instance_->name;
443 return "unkown";
444}
445
446template <class ServiceT>
447inline std::mutex & RosServiceNode<ServiceT>::getMutex()
448{
449 static std::mutex action_client_mutex;
450 return action_client_mutex;
451}
452
453template <class ServiceT>
454inline typename RosServiceNode<ServiceT>::ClientsRegistry & RosServiceNode<ServiceT>::getRegistry()
455{
456 static ClientsRegistry clients_registry;
457 return clients_registry;
458}
459
460} // namespace auto_apms_behavior_tree::core
Additional parameters specific to ROS 2 determined at runtime by TreeBuilder.
rclcpp::Time getCurrentTime() const
Get the current time using the associated ROS 2 node.
std::string getFullyQualifiedTreeNodeName(const BT::TreeNode *node, bool with_class_name=true) const
Create a string representing the detailed name of a behavior tree node.
std::string getServiceName() const
Get the name of the service this node connects with.
virtual bool setRequest(typename Request::SharedPtr &request)
Set the request to be sent to the ROS 2 service.
virtual BT::NodeStatus onResponseReceived(const typename Response::SharedPtr &response)
Callback invoked after the service response was received.
bool createClient(const std::string &service_name)
Create the client of the ROS 2 service.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
ADerived nodes implementing the static method RosServiceNode::providedPorts may call this method to a...
virtual BT::NodeStatus onFailure(ServiceNodeErrorCode error)
Callback invoked when one of the errors in ServiceNodeErrorCode occur.
RosServiceNode(const std::string &instance_name, const Config &config, Context context)
Constructor.
static BT::PortsList providedPorts()
If a behavior tree requires input/output data ports, the developer must define this method accordingl...
Core API for AutoAPMS's behavior tree implementation.
Definition behavior.hpp:32
const char * toStr(const ActionNodeErrorCode &err)
Convert the action error code to string.
Fundamental helper classes and utility functions.
std::string topic
Name of the ROS 2 communication interface to connect with.
std::chrono::duration< double > request_timeout
Period [s] (measured from sending a goal request) after the node aborts waiting for a server response...