mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 13:08:34 -04:00
Sub: use AP_Arming_Sub to disarm in motor test and failsafe
This commit is contained in:
parent
251a627095
commit
3a1984a893
@ -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();
|
||||
}
|
||||
}
|
||||
|
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user