mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: CPU failsafe set motors to min before logging error
This ensures that if the logging stalls the motors will have already been reduced to zero
This commit is contained in:
parent
80ba40d149
commit
9e12b01569
@ -51,7 +51,11 @@ void failsafe_check()
|
||||
// main loop ran. That means we're in trouble and should
|
||||
// disarm the motors.
|
||||
in_failsafe = true;
|
||||
|
||||
// reduce motors to minimum (we do not immediately disarm because we want to log the failure)
|
||||
if (motors.armed()) {
|
||||
motors.output_min();
|
||||
}
|
||||
// log an error
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_CPU,ERROR_CODE_FAILSAFE_OCCURRED);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user