ardupilot/ArduCopter/failsafe.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

85 lines
2.1 KiB
C++
Raw Normal View History

#include "Copter.h"
//
// failsafe support
// Andrew Tridgell, December 2011
//
// our failsafe strategy is to detect main loop lockup and disarm the motors
//
static bool failsafe_enabled;
static uint16_t failsafe_last_ticks;
static uint32_t failsafe_last_timestamp;
static bool in_failsafe;
//
// failsafe_enable - enable failsafe
//
void Copter::failsafe_enable()
{
failsafe_enabled = true;
failsafe_last_timestamp = micros();
}
//
// failsafe_disable - used when we know we are going to delay the mainloop significantly
//
void Copter::failsafe_disable()
{
failsafe_enabled = false;
}
2012-11-10 01:55:51 -04:00
//
// failsafe_check - this function is called from the core timer interrupt at 1kHz.
//
void Copter::failsafe_check()
{
uint32_t tnow = AP_HAL::micros();
2013-09-28 03:31:01 -03:00
const uint16_t ticks = scheduler.ticks();
if (ticks != failsafe_last_ticks) {
// the main loop is running, all is OK
failsafe_last_ticks = ticks;
failsafe_last_timestamp = tnow;
2014-10-30 01:23:09 -03:00
if (in_failsafe) {
in_failsafe = false;
LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_RESOLVED);
2014-10-30 01:23:09 -03:00
}
return;
}
2014-10-30 01:23:09 -03:00
if (!in_failsafe && failsafe_enabled && tnow - failsafe_last_timestamp > 2000000) {
2012-11-10 01:55:51 -04:00
// 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;
// reduce motors to minimum (we do not immediately disarm because we want to log the failure)
if (motors->armed()) {
motors->output_min();
}
2019-02-11 04:11:20 -04:00
LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED);
}
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();
}
}
2013-09-28 03:31:01 -03:00
}
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
/*
check for AFS failsafe check
*/
void Copter::afs_fs_check(void)
{
// perform AFS failsafe checks
g2.afs.check(last_radio_update_ms);
}
#endif