1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00

BUGFIX - Warning LED / arm prevention code fixes.

The old code was using f.ACC_CALIBRATED to mean 'flash the warning led'
and 'prevent arming'
There was another flag called f.OK_TO_ARM which really meant 'prevent
arming after failsafe unless using a switch to arm' - this meant the
comment in the code was incorrect since it did not mention the switch.
There was code which every ~71 minutes would set f.ACC_CALIBRATED to
FALSE and would toggle the LED, even when flying.
There was code that was run during every cycle that did not need to be
run when armed.
There was code that was run during every cycle which did not need to be
run when waiting for calibration to finish.
The warning light was toggled regardless of actual accelerometer
calibration state.

This commit fixes all that and prevents the user from arming after a
failsafe landing until the system is reset, regardless of wether a
switch is used to arm or not.

This commit also flashes the warning led during barometer calibration
and will not let you arm until it has completed.

Add a 5 second delay on startup to failsafe to prevent failsafe from
activating in the case of TX/RX gear with long bind procedures before
they send out valid data.

Failsafe now only prevents re-arming if a landing was forced.

In the case when you power on your RX without your TX on the beeper
sounds and failsafe warning ligts are activated.  When the FC then
detects a signal the lights go off and you can then arm.
This commit is contained in:
Dominic Clifton 2014-05-22 21:31:15 +01:00
parent d1be2ed5e2
commit d6c1ce323d
8 changed files with 121 additions and 39 deletions

109
src/mw.c
View file

@ -80,9 +80,47 @@ bool AccInflightCalibrationSavetoEEProm = false;
bool AccInflightCalibrationActive = false;
uint16_t InflightcalibratingA = 0;
bool isCalibrating()
{
#ifdef BARO
if (sensors(SENSOR_ACC) && !isBaroCalibrationComplete()) {
return false;
}
#endif
// Note: compass calibration is handled completely differently, outside of the main loop, see f.CALIBRATE_MAG
return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete());
}
static uint32_t warningLedTimer = 0;
void enableWarningLed(uint32_t currentTime)
{
if (warningLedTimer != 0) {
return; // already enabled
}
warningLedTimer = currentTime + 500000;
LED0_ON;
}
void disableWarningLed(void)
{
warningLedTimer = 0;
LED0_OFF;
}
void updateWarningLed(uint32_t currentTime)
{
if (warningLedTimer && (int32_t)(currentTime - warningLedTimer) >= 0) {
LED0_TOGGLE;
warningLedTimer = warningLedTimer + 500000;
}
}
void annexCode(void)
{
static uint32_t calibratedAccTime;
int32_t tmp, tmp2;
int32_t axis, prop1, prop2;
@ -160,17 +198,31 @@ void annexCode(void)
buzzer(batteryWarningEnabled); // external buzzer routine that handles buzzer events globally now
if ((!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete())) { // Calibration phasis
LED0_TOGGLE;
if (f.ARMED) {
LED0_ON;
} else {
if (f.ACC_CALIBRATED)
LED0_OFF;
if (f.ARMED)
LED0_ON;
if (isCalibrating()) {
LED0_TOGGLE;
f.OK_TO_ARM = 0;
}
checkTelemetryState();
f.OK_TO_ARM = 1;
if (!f.ARMED && !f.SMALL_ANGLE) {
f.OK_TO_ARM = 0;
}
if (f.OK_TO_ARM) {
disableWarningLed();
} else {
enableWarningLed(currentTime);
}
updateWarningLed(currentTime);
}
checkTelemetryState();
#ifdef LEDRING
if (feature(FEATURE_LED_RING)) {
static uint32_t LEDTime;
@ -181,15 +233,6 @@ void annexCode(void)
}
#endif
if ((int32_t)(currentTime - calibratedAccTime) >= 0) {
if (!f.SMALL_ANGLE) {
f.ACC_CALIBRATED = 0; // the multi uses ACC and is not calibrated or is too much inclinated
LED0_TOGGLE;
calibratedAccTime = currentTime + 500000;
} else {
f.ACC_CALIBRATED = 1;
}
}
handleSerial();
@ -204,21 +247,32 @@ void annexCode(void)
// TODO MCU temp
}
}
static void mwArm(void)
void mwDisarm(void)
{
if (isGyroCalibrationComplete() && f.ACC_CALIBRATED) {
// TODO: feature(FEATURE_FAILSAFE) && failsafeCnt < 2
// TODO: && ( !feature || ( feature && ( failsafecnt > 2) )
if (!f.ARMED) { // arm now!
if (f.ARMED)
f.ARMED = 0;
}
void mwArm(void)
{
if (f.OK_TO_ARM) {
if (f.ARMED) {
return;
}
if (!f.PREVENT_ARMING) {
f.ARMED = 1;
headFreeModeHold = heading;
return;
}
} else if (!f.ARMED) {
}
if (!f.ARMED) {
blinkLedAndSoundBeeper(2, 255, 1);
}
}
static void mwVario(void)
{
@ -256,6 +310,11 @@ void loop(void)
}
if (feature(FEATURE_FAILSAFE)) {
if (currentTime > FAILSAFE_POWER_ON_DELAY_US && !failsafe->vTable->isEnabled()) {
failsafe->vTable->enable();
}
failsafe->vTable->updateState();
}
@ -428,8 +487,6 @@ void loop(void)
f.HORIZON_MODE = 0;
}
if ((rcOptions[BOXARM]) == 0)
f.OK_TO_ARM = 1;
if (f.ANGLE_MODE || f.HORIZON_MODE) {
LED1_ON;
} else {