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

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

#include <service_client_handler.h>

Public Member Functions

 ServiceClientHandler (void)
 generic constructor
 
 ~ServiceClientHandler (void)
 generic destructor
 
ServiceClientHandleroperator= (const ServiceClientHandler &other)
 operator= More...
 
 ServiceClientHandler (const ServiceClientHandler &other)
 copy constructor More...
 
 ServiceClientHandler (ros::NodeHandle &nh, const std::string &address)
 constructor More...
 
void initialize (ros::NodeHandle &nh, const std::string &address)
 initializer More...
 
bool call (ServiceType &srv)
 "standard" synchronous call More...
 
bool call (ServiceType &srv, const int &attempts)
 "standard" synchronous call with repeats after failure More...
 
bool call (ServiceType &srv, const int &attempts, const double &repeat_delay)
 "standard" synchronous call with repeats after failure More...
 
std::future< ServiceType > callAsync (ServiceType &srv)
 asynchronous call More...
 
std::future< ServiceType > callAsync (ServiceType &srv, const int &attempts)
 asynchronous call with repeats after failure More...
 
std::future< ServiceType > callAsync (ServiceType &srv, const int &attempts, const double &repeat_delay)
 asynchronous call with repeats after failure More...
 

Detailed Description

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

user wrapper of the service client handler implementation

Constructor & Destructor Documentation

◆ ServiceClientHandler() [1/2]

template<class ServiceType >
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler ( const ServiceClientHandler< ServiceType > &  other)

copy constructor

Parameters
other

◆ ServiceClientHandler() [2/2]

template<class ServiceType >
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler ( ros::NodeHandle &  nh,
const std::string &  address 
)

constructor

Parameters
nhROS node handler
addressservice address

Member Function Documentation

◆ call() [1/3]

template<class ServiceType >
bool mrs_lib::ServiceClientHandler< ServiceType >::call ( ServiceType &  srv)

"standard" synchronous call

Parameters
srvdata
Returns
true when success

◆ call() [2/3]

template<class ServiceType >
bool mrs_lib::ServiceClientHandler< ServiceType >::call ( ServiceType &  srv,
const int &  attempts 
)

"standard" synchronous call with repeats after failure

Parameters
srvdata
attemptshow many attempts for the call
Returns
true when success

◆ call() [3/3]

template<class ServiceType >
bool mrs_lib::ServiceClientHandler< ServiceType >::call ( ServiceType &  srv,
const int &  attempts,
const double &  repeat_delay 
)

"standard" synchronous call with repeats after failure

Parameters
srvdata
attemptshow many attempts for the call
repeat_delayhow long to wait before repeating the call
Returns
true when success

◆ callAsync() [1/3]

template<class ServiceType >
std::future< ServiceType > mrs_lib::ServiceClientHandler< ServiceType >::callAsync ( ServiceType &  srv)

asynchronous call

Parameters
srvdata
Returns
future result

◆ callAsync() [2/3]

template<class ServiceType >
std::future< ServiceType > mrs_lib::ServiceClientHandler< ServiceType >::callAsync ( ServiceType &  srv,
const int &  attempts 
)

asynchronous call with repeats after failure

Parameters
srvdata
attemptshow many attemps for the call
Returns
future result

◆ callAsync() [3/3]

template<class ServiceType >
std::future< ServiceType > mrs_lib::ServiceClientHandler< ServiceType >::callAsync ( ServiceType &  srv,
const int &  attempts,
const double &  repeat_delay 
)

asynchronous call with repeats after failure

Parameters
srvdata
attemptshow many attemps for the call
repeat_delayhow long to wait before repeating the call
Returns
future result

◆ initialize()

template<class ServiceType >
void mrs_lib::ServiceClientHandler< ServiceType >::initialize ( ros::NodeHandle &  nh,
const std::string &  address 
)

initializer

Parameters
nhROS node handler
addressservice address

◆ operator=()

template<class ServiceType >
ServiceClientHandler< ServiceType > & mrs_lib::ServiceClientHandler< ServiceType >::operator= ( const ServiceClientHandler< ServiceType > &  other)

operator=

Parameters
other
Returns

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