#include <service_caller.h>
Public Member Functions | |
bool | isCalibrated () |
QueryCalibrationServiceCaller (ros::NodeHandle &nh) | |
QueryCalibrationServiceCaller (ros::NodeHandle &nh, std::string &service_name) | |
QueryCalibrationServiceCaller (XmlRpc::XmlRpcValue &controllers, ros::NodeHandle &nh) | |
![]() | |
void | callService () |
control_msgs::QueryCalibrationState & | getService () |
bool | isCalling () |
ServiceCallerBase (ros::NodeHandle &nh, const std::string &service_name="") | |
ServiceCallerBase (ros::NodeHandle &nh, std::string &service_name) | |
ServiceCallerBase (XmlRpc::XmlRpcValue &controllers, ros::NodeHandle &nh, const std::string &service_name="") | |
~ServiceCallerBase () | |
Additional Inherited Members | |
![]() | |
void | callingThread () |
![]() | |
ros::ServiceClient | client_ |
int | fail_count_ |
int | fail_limit_ |
std::mutex | mutex_ |
control_msgs::QueryCalibrationState | service_ |
std::string | service_name_ |
std::thread * | thread_ |
Definition at line 192 of file service_caller.h.
|
inlineexplicit |
Definition at line 195 of file service_caller.h.
|
inline |
Definition at line 199 of file service_caller.h.
|
inline |
Definition at line 203 of file service_caller.h.
|
inline |
Definition at line 207 of file service_caller.h.