mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
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 | |
ServiceClientHandler & | operator= (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... | |
user wrapper of the service client handler implementation
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler | ( | const ServiceClientHandler< ServiceType > & | other | ) |
copy constructor
other |
mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler | ( | ros::NodeHandle & | nh, |
const std::string & | address | ||
) |
constructor
nh | ROS node handler |
address | service address |
bool mrs_lib::ServiceClientHandler< ServiceType >::call | ( | ServiceType & | srv | ) |
"standard" synchronous call
srv | data |
bool mrs_lib::ServiceClientHandler< ServiceType >::call | ( | ServiceType & | srv, |
const int & | attempts | ||
) |
"standard" synchronous call with repeats after failure
srv | data |
attempts | how many attempts for the call |
bool mrs_lib::ServiceClientHandler< ServiceType >::call | ( | ServiceType & | srv, |
const int & | attempts, | ||
const double & | repeat_delay | ||
) |
"standard" synchronous call with repeats after failure
srv | data |
attempts | how many attempts for the call |
repeat_delay | how long to wait before repeating the call |
std::future< ServiceType > mrs_lib::ServiceClientHandler< ServiceType >::callAsync | ( | ServiceType & | srv | ) |
asynchronous call
srv | data |
std::future< ServiceType > mrs_lib::ServiceClientHandler< ServiceType >::callAsync | ( | ServiceType & | srv, |
const int & | attempts | ||
) |
asynchronous call with repeats after failure
srv | data |
attempts | how many attemps for the call |
std::future< ServiceType > mrs_lib::ServiceClientHandler< ServiceType >::callAsync | ( | ServiceType & | srv, |
const int & | attempts, | ||
const double & | repeat_delay | ||
) |
asynchronous call with repeats after failure
srv | data |
attempts | how many attemps for the call |
repeat_delay | how long to wait before repeating the call |
void mrs_lib::ServiceClientHandler< ServiceType >::initialize | ( | ros::NodeHandle & | nh, |
const std::string & | address | ||
) |
initializer
nh | ROS node handler |
address | service address |
ServiceClientHandler< ServiceType > & mrs_lib::ServiceClientHandler< ServiceType >::operator= | ( | const ServiceClientHandler< ServiceType > & | other | ) |
operator=
other |