21 #include <std_srvs/Trigger.h> 26 #include <prbt_hardware_support/SendBrakeTestResult.h> 27 #include <prbt_hardware_support/BrakeTest.h> 43 int main(
int argc,
char **argv)
45 ros::init(argc, argv,
"brake_test_executor");
60 using std::placeholders::_1;
62 std::bind(triggerServiceCall<ros::ServiceClient>, hold_client),
63 std::bind(executeBrakeTestCall<ros::ServiceClient>, brake_test_execute_client),
64 std::bind(triggerServiceCall<ros::ServiceClient>, unhold_client),
65 std::bind(sendBrakeTestResultCall<ros::ServiceClient>, brake_test_result_client, _1));
69 &brake_test_executor);
static const std::string BRAKE_TEST_RESULT_SERVICE_NAME
static bool detectRobotMotion(double timeout_s=DEFAULT_ROBOT_MOTION_TIMEOUT_S)
return true if a robot motion was detected, false otherwise.
bool executeBrakeTest(BrakeTest::Request &req, BrakeTest::Response &response)
int main(int argc, char **argv)
Provides service to execute a braketest.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const std::string EXECUTE_BRAKETEST_SERVICE_NAME
Triggers execution of brake tests only if the controller is not executing a trajectory.
static constexpr double DEFAULT_ROBOT_MOTION_TIMEOUT_S
ROSCPP_DECL void spin(Spinner &spinner)
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
static const std::string BRAKETEST_ADAPTER_SERVICE_NAME
static const std::string CONTROLLER_HOLD_MODE_SERVICE_NAME
static const std::string CONTROLLER_UNHOLD_MODE_SERVICE_NAME