19 template <
class ServiceType>
21 : impl_(std::make_shared<
Impl>(node, address, qos, node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive)))
25 template <
class ServiceType>
30 template <
class ServiceType>
32 const rclcpp::CallbackGroup::SharedPtr& callback_group)
33 : impl_(std::make_shared<
Impl>(node, address, qos, callback_group))
37 template <
class ServiceType>
39 const rclcpp::CallbackGroup::SharedPtr& callback_group)
48 template <
class ServiceType>
49 std::optional<std::shared_ptr<typename ServiceType::Response>>
54 RCLCPP_ERROR(rclcpp::get_logger(
"ServiceClientHandler"),
"Not initialized, cannot use callSync()!");
57 return impl_->callSync(request);
64 template <
class ServiceType>
65 std::optional<std::shared_future<std::shared_ptr<typename ServiceType::Response>>>
70 RCLCPP_ERROR(rclcpp::get_logger(
"ServiceClientHandler"),
"Not initialized, cannot use callSync()!");
73 return impl_->callAsync(request);
87 template <
class ServiceType>
100 Impl(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::QoS& qos,
const rclcpp::CallbackGroup::SharedPtr& callback_group)
101 : callback_group_(callback_group), service_client_(node->create_client<ServiceType>(address, qos, callback_group))
112 std::optional<std::shared_ptr<typename ServiceType::Response>>
callSync(
const std::shared_ptr<typename ServiceType::Request>& request)
115 if (!service_client_->service_is_ready())
119 const auto future_msg = service_client_->async_send_request(request).future.share();
123 if (!future_msg.valid())
127 return future_msg.get();
137 std::optional<std::shared_future<std::shared_ptr<typename ServiceType::Response>>>
callAsync(
const std::shared_ptr<typename ServiceType::Request>& request)
140 if (!service_client_->service_is_ready())
143 const auto future = service_client_->async_send_request(request).future.share();
154 rclcpp::CallbackGroup::SharedPtr callback_group_;
155 typename rclcpp::Client<ServiceType>::SharedPtr service_client_;
implementation of the service client handler
Definition service_client_handler.hpp:89
std::optional< std::shared_future< std::shared_ptr< typename ServiceType::Response > > > callAsync(const std::shared_ptr< typename ServiceType::Request > &request)
asynchronous service call
Definition service_client_handler.hpp:137
std::optional< std::shared_ptr< typename ServiceType::Response > > callSync(const std::shared_ptr< typename ServiceType::Request > &request)
"classic" synchronous service call
Definition service_client_handler.hpp:112
Impl(rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::QoS &qos, const rclcpp::CallbackGroup::SharedPtr &callback_group)
constructor
Definition service_client_handler.hpp:100
user wrapper of the service client handler implementation
Definition service_client_handler.h:23
ServiceClientHandler()
Default constructor to avoid having to use pointers.
Definition service_client_handler.hpp:26
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:50
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:66
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Defines ServiceClientHandler and related convenience classes for upgrading the ROS service client.