Sub: use AP_Arming_Sub to disarm in motor test and failsafe

This commit is contained in:
Willian Galvani 2020-02-19 15:31:12 -03:00 committed by Jacob Walser
parent 251a627095
commit 3a1984a893
2 changed files with 2 additions and 2 deletions

View File

@ -58,7 +58,7 @@ void Sub::mainloop_failsafe_check()
// disarm motors every second
failsafe_last_timestamp = tnow;
if (motors.armed()) {
motors.armed(false);
arming.disarm();
motors.output();
}
}

View File

@ -70,7 +70,7 @@ bool Sub::verify_motor_test()
if (!pass) {
ap.motor_test = false;
motors.armed(false); // disarm motors
arming.disarm(); // disarm motors
last_do_motor_test_fail_ms = AP_HAL::millis();
return false;
}