mirror of https://github.com/ArduPilot/ardupilot
62 lines
1.6 KiB
Plaintext
62 lines
1.6 KiB
Plaintext
// -*- 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 disarm the motors
|
|
//
|
|
|
|
static bool failsafe_enabled = true;
|
|
static uint16_t failsafe_last_mainLoop_count;
|
|
static uint32_t failsafe_last_timestamp;
|
|
static bool in_failsafe;
|
|
|
|
//
|
|
// failsafe_enable - enable failsafe
|
|
//
|
|
void failsafe_enable()
|
|
{
|
|
failsafe_enabled = true;
|
|
failsafe_last_timestamp = micros();
|
|
}
|
|
|
|
//
|
|
// failsafe_disable - used when we know we are going to delay the mainloop significantly
|
|
//
|
|
void failsafe_disable()
|
|
{
|
|
failsafe_enabled = false;
|
|
}
|
|
|
|
//
|
|
// failsafe_check - this function is called from the core timer interrupt at 1kHz.
|
|
//
|
|
void failsafe_check()
|
|
{
|
|
uint32_t tnow = hal.scheduler->micros();
|
|
|
|
if (mainLoop_count != failsafe_last_mainLoop_count) {
|
|
// the main loop is running, all is OK
|
|
failsafe_last_mainLoop_count = mainLoop_count;
|
|
failsafe_last_timestamp = tnow;
|
|
in_failsafe = false;
|
|
return;
|
|
}
|
|
|
|
if (failsafe_enabled && tnow - failsafe_last_timestamp > 2000000) {
|
|
// motors are running but we have gone 2 second since the
|
|
// main loop ran. That means we're in trouble and should
|
|
// disarm the motors.
|
|
in_failsafe = true;
|
|
}
|
|
|
|
if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) {
|
|
// disarm motors every second
|
|
failsafe_last_timestamp = tnow;
|
|
if(motors.armed()) {
|
|
motors.armed(false);
|
|
motors.output();
|
|
}
|
|
}
|
|
}
|