8#include <rclcpp/rclcpp.hpp>
13#include <mrs_lib/coro/internal/thread_local_continuation_scheduler.hpp>
14#include <mrs_lib/coro/task.hpp>
18 template <
class ServiceType>
19 class ServiceClientHandler;
23 template <
typename ServiceType>
24 requires(rosidl_generator_traits::is_service<ServiceType>::value)
25 class [[nodiscard(
"This service call is only performed when `co_await`ed.")]] ServiceAwaitable;
33 template <
class ServiceType>
49 ServiceClientHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::QoS& qos = rclcpp::ServicesQoS());
69 ServiceClientHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::QoS& qos,
70 const rclcpp::CallbackGroup::SharedPtr& callback_group);
81 ServiceClientHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::CallbackGroup::SharedPtr& callback_group);
96 std::optional<std::shared_ptr<typename ServiceType::Response>>
callSync(
const std::shared_ptr<typename ServiceType::Request>& request);
105 std::optional<std::shared_future<std::shared_ptr<typename ServiceType::Response>>>
callAsync(
const std::shared_ptr<typename ServiceType::Request>& request);
141 template <
typename RepT =
int64_t,
typename RatioT = std::milli>
142 bool waitForService(std::chrono::duration<RepT, RatioT> timeout = std::chrono::seconds(1));
153 std::shared_ptr<Impl> impl_;
implementation of the service client handler
Definition service_client_handler.hpp:308
user wrapper of the service client handler implementation
Definition service_client_handler.h:35
ServiceClientHandler()
Default constructor to avoid having to use pointers.
Definition service_client_handler.hpp:187
std::optional< std::shared_ptr< typename ServiceType::Response > > callSync(const std::shared_ptr< typename ServiceType::Request > &request)
Synchronous (blocking) call of the service.
Definition service_client_handler.hpp:211
std::string getServiceName() const
Returns the name of the service this client connects to.
Definition service_client_handler.hpp:255
bool waitForService(std::chrono::duration< RepT, RatioT > timeout=std::chrono::seconds(1))
Waits for the service to be available.
Definition service_client_handler.hpp:271
std::optional< std::shared_future< std::shared_ptr< typename ServiceType::Response > > > callAsync(const std::shared_ptr< typename ServiceType::Request > &request)
Asynchronous (non-blocking) call of the service.
Definition service_client_handler.hpp:227
bool isServiceReady() const
Checks if the service is available.
Definition service_client_handler.hpp:285
Task< std::optional< std::shared_ptr< typename ServiceType::Response > > > callAwaitable(std::shared_ptr< typename ServiceType::Request > request)
Awaitable call of the service.
Definition service_client_handler.hpp:241
Task type for creating coroutines.
Definition task.hpp:313
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Implements ServiceClientHandler and related convenience classes for upgrading the ROS service client.