commander: add support for DO_MOTOR_TEST

- add an optional timeout to test_motor
- enforce a timeout when receiving DO_MOTOR_TEST
- limitation: DO_MOTOR_TEST can only control the MAIN outputs
This commit is contained in:
Beat Küng
2019-10-21 12:12:07 +02:00
parent eb6a9bd488
commit 285ae608a5
7 changed files with 91 additions and 14 deletions
+14 -7
View File
@@ -48,10 +48,10 @@
extern "C" __EXPORT int motor_test_main(int argc, char *argv[]);
static void motor_test(unsigned channel, float value, uint8_t driver_instance);
static void motor_test(unsigned channel, float value, uint8_t driver_instance, int timeout_ms);
static void usage(const char *reason);
void motor_test(unsigned channel, float value, uint8_t driver_instance)
void motor_test(unsigned channel, float value, uint8_t driver_instance, int timeout_ms)
{
test_motor_s test_motor{};
test_motor.timestamp = hrt_absolute_time();
@@ -59,6 +59,7 @@ void motor_test(unsigned channel, float value, uint8_t driver_instance)
test_motor.value = value;
test_motor.action = value >= 0.f ? test_motor_s::ACTION_RUN : test_motor_s::ACTION_STOP;
test_motor.driver_instance = driver_instance;
test_motor.timeout_ms = timeout_ms;
uORB::PublicationQueued<test_motor_s> test_motor_pub{ORB_ID(test_motor)};
test_motor_pub.publish(test_motor);
@@ -90,6 +91,7 @@ Note: this can only be used for drivers which support the motor_test uorb topic
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Set motor(s) to a specific output value");
PRINT_MODULE_USAGE_PARAM_INT('m', -1, 0, 7, "Motor to test (0...7, all if not specified)", true);
PRINT_MODULE_USAGE_PARAM_INT('p', 0, 0, 100, "Power (0...100)", true);
PRINT_MODULE_USAGE_PARAM_INT('t', 0, 0, 100, "Timeout in seconds (default=no timeout)", true);
PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 4, "driver instance", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop all motors");
PRINT_MODULE_USAGE_COMMAND_DESCR("iterate", "Iterate all motors starting and stopping one after the other");
@@ -103,11 +105,12 @@ int motor_test_main(int argc, char *argv[])
float value = 0.0f;
uint8_t driver_instance = 0;
int ch;
int timeout_ms = 0;
int myoptind = 1;
const char *myoptarg = NULL;
while ((ch = px4_getopt(argc, argv, "i:m:p:", &myoptind, &myoptarg)) != EOF) {
while ((ch = px4_getopt(argc, argv, "i:m:p:t:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'i':
@@ -131,6 +134,10 @@ int motor_test_main(int argc, char *argv[])
value = ((float)lval) / 100.f;
break;
case 't':
timeout_ms = strtol(myoptarg, NULL, 0) * 1000;
break;
default:
usage(NULL);
return 1;
@@ -148,9 +155,9 @@ int motor_test_main(int argc, char *argv[])
value = 0.15f;
for (int i = 0; i < 8; ++i) {
motor_test(i, value, driver_instance);
motor_test(i, value, driver_instance, 0);
px4_usleep(500000);
motor_test(i, -1.f, driver_instance);
motor_test(i, -1.f, driver_instance, 0);
px4_usleep(10000);
}
@@ -171,12 +178,12 @@ int motor_test_main(int argc, char *argv[])
if (run_test) {
if (channel < 0) {
for (int i = 0; i < 8; ++i) {
motor_test(i, value, driver_instance);
motor_test(i, value, driver_instance, timeout_ms);
px4_usleep(10000);
}
} else {
motor_test(channel, value, driver_instance);
motor_test(channel, value, driver_instance, timeout_ms);
}
}