mirror of https://github.com/ArduPilot/ardupilot
Sub: Motor-test: change disarm method on motor test timeout
This commit is contained in:
parent
1d14ea4f54
commit
88c43e43d5
|
@ -70,7 +70,7 @@ bool Sub::verify_motor_test()
|
|||
|
||||
if (!pass) {
|
||||
ap.motor_test = false;
|
||||
motors.armed(false); // disarm motors
|
||||
AP::arming().disarm(AP_Arming::Method::MOTORTEST);
|
||||
last_do_motor_test_fail_ms = AP_HAL::millis();
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue