8#include <rclcpp/rclcpp.hpp>
21 template <
class ServiceType>
37 ServiceClientHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::QoS& qos = rclcpp::ServicesQoS());
57 ServiceClientHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::QoS& qos,
const rclcpp::CallbackGroup::SharedPtr& callback_group);
68 ServiceClientHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const rclcpp::CallbackGroup::SharedPtr& callback_group);
83 std::optional<std::shared_ptr<typename ServiceType::Response>>
callSync(
const std::shared_ptr<typename ServiceType::Request>& request);
92 std::optional<std::shared_future<std::shared_ptr<typename ServiceType::Response>>>
callAsync(
const std::shared_ptr<typename ServiceType::Request>& request);
96 std::shared_ptr<Impl> impl_;
implementation of the service client handler
Definition service_client_handler.hpp:85
user wrapper of the service client handler implementation
Definition service_client_handler.h:22
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:48
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:63
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.