From 991bcf6fd91f6407bcd0fe3dbe58398b4baa7c6e Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Tue, 4 Apr 2017 20:24:25 -0400 Subject: [PATCH] Add MOTOR_TEST_ORDER enum and update DO_MOTOR_TEST params --- message_definitions/v1.0/common.xml | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index bf4af5b0d3..88369e34c9 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1137,12 +1137,12 @@ Mission command to perform motor test - motor sequence number (a number from 1 to max number of motors on the vehicle) + motor number (a number from 1 to max number of motors on the vehicle) throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) throttle timeout (in seconds) - Empty - Empty + motor count (number of motors to test to test in sequence, waiting for the timeout above between them; 0=1 motor, 1=1 motor, 2=2 motors...) + motor test order (See MOTOR_TEST_ORDER enum) Empty @@ -2311,6 +2311,18 @@ + + + default autopilot motor test method + + + motor numbers are specified as their index in a predefined vehicle-specific sequence + + + motor numbers are specified as the output as labeled on the board + + + throttle as a percentage from 0 ~ 100