mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 01:44:00 -04:00
Sub: bugfixup motor test
This commit is contained in:
parent
5bfea69c48
commit
ee36509cb8
@ -217,7 +217,8 @@ bool Sub::handle_do_motor_test(mavlink_command_long_t command) {
|
||||
float throttle_type = command.param2;
|
||||
float throttle = command.param3;
|
||||
// float timeout_s = command.param4; // not used
|
||||
float test_type = command.param5;
|
||||
// float motor_count = command.param5;
|
||||
float test_type = command.param6;
|
||||
|
||||
if (!is_equal(test_type, (float)MOTOR_TEST_ORDER_BOARD) &&
|
||||
!is_equal(test_type, (float)MOTOR_TEST_ORDER_DEFAULT)) {
|
||||
|
Loading…
Reference in New Issue
Block a user