mirror of https://github.com/ArduPilot/ardupilot
APM: added failsafe support
we now pass all channels through at 50Hz if the main loop stops running, regardless of why. This gives us a reasonable failsafe, as long as the low level RC library is still working, and interrupts don't get completely disabled.
This commit is contained in:
parent
e687ce9b3d
commit
29fa78214b
|
@ -0,0 +1,45 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
failsafe support
|
||||
Andrew Tridgell, December 2011
|
||||
*/
|
||||
|
||||
/*
|
||||
our failsafe strategy is to detect main loop lockup and switch to
|
||||
passing inputs straight from the RC inputs to RC outputs.
|
||||
*/
|
||||
|
||||
/*
|
||||
this failsafe_check function is called from the core timer interrupt
|
||||
at 1kHz.
|
||||
*/
|
||||
void failsafe_check(uint32_t tnow)
|
||||
{
|
||||
static uint16_t last_mainLoop_count;
|
||||
static uint32_t last_timestamp;
|
||||
static bool in_failsafe;
|
||||
|
||||
if (mainLoop_count != last_mainLoop_count) {
|
||||
// the main loop is running, all is OK
|
||||
last_mainLoop_count = mainLoop_count;
|
||||
last_timestamp = tnow;
|
||||
in_failsafe = false;
|
||||
return;
|
||||
}
|
||||
|
||||
if (tnow - last_timestamp > 200000) {
|
||||
// we have gone at least 0.2 seconds since the main loop
|
||||
// ran. That means we're in trouble, or perhaps are in
|
||||
// an initialisation routine or log erase. Start passing RC
|
||||
// inputs through to outputs
|
||||
in_failsafe = true;
|
||||
}
|
||||
|
||||
if (in_failsafe && tnow - last_timestamp > 20000) {
|
||||
// pass RC inputs to outputs every 20ms
|
||||
last_timestamp = tnow;
|
||||
for (uint8_t ch=0; ch<8; ch++) {
|
||||
APM_RC.OutputCh(ch, APM_RC.InputCh(ch));
|
||||
}
|
||||
}
|
||||
}
|
|
@ -46,6 +46,9 @@ MENU(main_menu, THISFIRMWARE, main_menu_commands);
|
|||
// the user wants the CLI. It never exits
|
||||
static void run_cli(void)
|
||||
{
|
||||
// disable the failsafe code in the CLI
|
||||
timer_scheduler.set_failsafe(NULL);
|
||||
|
||||
while (1) {
|
||||
main_menu.run();
|
||||
}
|
||||
|
@ -119,9 +122,8 @@ static void init_ardupilot()
|
|||
// Initialize the timer scheduler to use the ISR registry.
|
||||
//
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
timer_scheduler.init( & isr_registry );
|
||||
#endif
|
||||
timer_scheduler.set_failsafe(failsafe_check);
|
||||
|
||||
//
|
||||
// Check the EEPROM format version before loading any parameters from EEPROM.
|
||||
|
|
Loading…
Reference in New Issue