|
rm_control
|
#include <service_caller.h>


Public Member Functions | |
| SwitchControllersServiceCaller (ros::NodeHandle &nh) | |
| void | startControllers (const std::vector< std::string > &controllers) |
| void | stopControllers (const std::vector< std::string > &controllers) |
| bool | getOk () |
Public Member Functions inherited from rm_common::ServiceCallerBase< controller_manager_msgs::SwitchController > | |
| 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 () | |
| void | callService () |
| controller_manager_msgs::SwitchController & | getService () |
| bool | isCalling () |
Additional Inherited Members | |
Protected Member Functions inherited from rm_common::ServiceCallerBase< controller_manager_msgs::SwitchController > | |
| void | callingThread () |
Protected Attributes inherited from rm_common::ServiceCallerBase< controller_manager_msgs::SwitchController > | |
| std::string | service_name_ |
| ros::ServiceClient | client_ |
| controller_manager_msgs::SwitchController | service_ |
| std::thread * | thread_ |
| std::mutex | mutex_ |
| int | fail_count_ |
| int | fail_limit_ |
|
inlineexplicit |
|
inline |
|
inline |
|
inline |