Skip to content
Snippets Groups Projects
Commit 9e12b015 authored by Randy Mackay's avatar Randy Mackay
Browse files

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
parent 80ba40d1
No related branches found
No related tags found
No related merge requests found
......@@ -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);
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment