mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
mrs_lib::ServiceClientHandler< ServiceType > Class Template Reference

user wrapper of the service client handler implementation More...

#include <service_client_handler.h>

Classes

class  Impl
 implementation of the service client handler More...
 

Public Member Functions

 ServiceClientHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::QoS &qos=rclcpp::ServicesQoS())
 The main constructor with all the options.
 
 ServiceClientHandler ()
 Default constructor to avoid having to use pointers.
 
 ServiceClientHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::QoS &qos, const rclcpp::CallbackGroup::SharedPtr &callback_group)
 A convenience constructor.
 
 ServiceClientHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::CallbackGroup::SharedPtr &callback_group)
 A convenience constructor.
 
std::optional< std::shared_ptr< typename ServiceType::Response > > callSync (const std::shared_ptr< typename ServiceType::Request > &request)
 Synchronous (blocking) call of the service.
 
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.
 

Detailed Description

template<class ServiceType>
class mrs_lib::ServiceClientHandler< ServiceType >

user wrapper of the service client handler implementation

Constructor & Destructor Documentation

◆ ServiceClientHandler() [1/4]

template<class ServiceType >
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler ( rclcpp::Node::SharedPtr &  node,
const std::string &  address,
const rclcpp::QoS &  qos = rclcpp::ServicesQoS() 
)

The main constructor with all the options.

This variant initializes a new MutuallyExclusive callback group for the service client, which is the intended default behavior to avoid deadlocks when using the callSync() method. For a more detailed explanation of the parameters, see the documentation of rclcpp::Node::create_client.

Parameters
nodeROS node handler.
addressName of the service.
qosQOS Communication quality of service profile.

◆ ServiceClientHandler() [2/4]

template<class ServiceType >
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler ( )

Default constructor to avoid having to use pointers.

It does nothing and the object it constructs will also do nothing. Use some of the other constructors for a construction of an actually usable object.

◆ ServiceClientHandler() [3/4]

template<class ServiceType >
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler ( rclcpp::Node::SharedPtr &  node,
const std::string &  address,
const rclcpp::QoS &  qos,
const rclcpp::CallbackGroup::SharedPtr &  callback_group 
)

A convenience constructor.

This is just for convenience when you want to specify the callback group.

Parameters
nodeROS node handler.
addressName of the service.
qosQOS Communication quality of service profile.
callback_groupCallback group used internally by the node for the response callback. Set to nullptr to use the default one.

◆ ServiceClientHandler() [4/4]

template<class ServiceType >
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler ( rclcpp::Node::SharedPtr &  node,
const std::string &  address,
const rclcpp::CallbackGroup::SharedPtr &  callback_group 
)

A convenience constructor.

This is just for convenience when you want to specify the callback group but don't care about QoS.

Parameters
nodeROS node handler.
addressName of the service.
callback_groupCallback group used internally by the node for the response callback. Set to nullptr to use the default one.

Member Function Documentation

◆ callAsync()

template<class ServiceType >
std::optional< std::shared_future< std::shared_ptr< typename ServiceType::Response > > > mrs_lib::ServiceClientHandler< ServiceType >::callAsync ( const std::shared_ptr< typename ServiceType::Request > &  request)

Asynchronous (non-blocking) call of the service.

Parameters
requestThe service request to be sent with the call
Returns
Optional shared pointer to the result or std::nullopt if the call failed

◆ callSync()

template<class ServiceType >
std::optional< std::shared_ptr< typename ServiceType::Response > > mrs_lib::ServiceClientHandler< ServiceType >::callSync ( const std::shared_ptr< typename ServiceType::Request > &  request)

Synchronous (blocking) call of the service.

This method will block until the service call returns.

Parameters
requestThe service request to be sent with the call
Returns
Optional shared pointer to the result or std::nullopt if the call failed
Warning
Take care when using this method! Make sure that the thread and callback group that you're calling it from is not the same as the thread/callback group of the service client or the service server being called! This can typically happen if you call this from another callback or if you're using the SingleThreadedExecutor, and will lead to a deadlock.

The documentation for this class was generated from the following files: