1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00

Added beeps to indicate the reason for arming being disabled.

This commit is contained in:
mikeller 2017-07-02 17:13:12 +12:00
parent 31c639b13f
commit 67acc6c7ec
12 changed files with 109 additions and 61 deletions

View file

@ -17,6 +17,7 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
@ -35,6 +36,7 @@
#include "drivers/gyro_sync.h"
#include "drivers/light_led.h"
#include "drivers/system.h"
#include "drivers/time.h"
#include "drivers/transponder_ir.h"
@ -111,7 +113,7 @@ static bool reverseMotors = false;
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
bool isRXDataNew;
static bool armingCalibrationWasInitialised;
static int lastArmingDisabledReason = 0;
PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig, PG_THROTTLE_CORRECTION_CONFIG, 0);
@ -141,6 +143,11 @@ static bool isCalibrating()
return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete());
}
void resetArmingDisabled(void)
{
lastArmingDisabledReason = 0;
}
void updateArmingStatus(void)
{
if (ARMING_FLAG(ARMED)) {
@ -188,8 +195,6 @@ void updateArmingStatus(void)
void disarm(void)
{
armingCalibrationWasInitialised = false;
if (ARMING_FLAG(ARMED)) {
DISABLE_ARMING_FLAG(ARMED);
@ -205,12 +210,8 @@ void disarm(void)
void tryArm(void)
{
static bool firstArmingCalibrationWasCompleted;
if (armingConfig()->gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
gyroStartCalibration();
armingCalibrationWasInitialised = true;
firstArmingCalibrationWasCompleted = true;
if (armingConfig()->gyro_cal_on_first_arm) {
gyroStartCalibration(true);
}
updateArmingStatus();
@ -233,7 +234,7 @@ void tryArm(void)
pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED);
}
}
}
}
#endif
ENABLE_ARMING_FLAG(ARMED);
@ -242,6 +243,8 @@ void tryArm(void)
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
lastArmingDisabledReason = 0;
//beep to indicate arming
#ifdef GPS
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) {
@ -252,12 +255,15 @@ void tryArm(void)
#else
beeper(BEEPER_ARMING);
#endif
} else {
if (!isFirstArmingGyroCalibrationRunning()) {
int armingDisabledReason = ffs(getArmingDisableFlags());
if (lastArmingDisabledReason != armingDisabledReason) {
lastArmingDisabledReason = armingDisabledReason;
return;
}
if (!ARMING_FLAG(ARMED)) {
beeperConfirmationBeeps(1);
beeperWarningBeeps(armingDisabledReason);
}
}
}
}