Sub: Motor-test: change disarm method on motor test timeout
This commit is contained in:
parent
68274ff996
commit
d5ec5f1dfc
@ -70,7 +70,7 @@ bool Sub::verify_motor_test()
|
|||||||
|
|
||||||
if (!pass) {
|
if (!pass) {
|
||||||
ap.motor_test = false;
|
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();
|
last_do_motor_test_fail_ms = AP_HAL::millis();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user