18 #ifndef PRBT_HARDWARE_SUPPORT_CANOPEN_BRAKETEST_ADAPTER_H 19 #define PRBT_HARDWARE_SUPPORT_CANOPEN_BRAKETEST_ADAPTER_H 26 #include <canopen_chain_node/GetObject.h> 27 #include <canopen_chain_node/SetObject.h> 29 #include <prbt_hardware_support/BrakeTest.h> 65 #endif // PRBT_HARDWARE_SUPPORT_CANOPEN_BRAKETEST_ADAPTER_H
void checkBrakeTestResultForNode(const std::string &node_name)
BrakeTestStatus getBrakeTestStatusForNode(const std::string &node_name)
bool triggerBrakeTests(BrakeTest::Request &, BrakeTest::Response &response)
ros::ServiceClient canopen_srv_set_client_
ros::Duration getMaximumBrakeTestDuration(const std::vector< std::string > &node_names)
ros::ServiceClient canopen_srv_get_client_
ros::ServiceServer brake_test_srv_
Service which triggers brake tests for all joints.
CANOpenBrakeTestAdapter(ros::NodeHandle &nh)
Executes the brake test for all joints. A brake test is triggered via service call.
void triggerBrakeTestForNode(const std::string &node_name)
std::vector< std::string > getNodeNames()
ros::Duration getBrakeTestDuration(const std::string &node_name)
std::pair< int8_t, std::string > BrakeTestStatus