Cleanup status indicator code.
This primarily is to avaoid stalling the main loop when beeping and flashing. This is needed because oneshot ESCs do not receive updates when the main loop is stalled. Additionally the beeper code for sticks held in disarm position is changed since it also clashed with profile selection. Now profile selections can be seen and heard clearly. Other subsections of the system that changed the LED0 state while the main loop is running have been updated to use the status indicator API instead of blindly hitting the hardware which previously caused lots of odd LED flashing behaviour - now it is consistent.
This commit is contained in:
parent
22a98af25a
commit
e6733b4dfc
|
@ -44,7 +44,7 @@
|
|||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
|
@ -852,7 +852,7 @@ void readEEPROMAndNotify(void)
|
|||
{
|
||||
// re-read written data
|
||||
readEEPROM();
|
||||
blinkLedAndSoundBeeper(15, 20, 1);
|
||||
beeperConfirmationBeeps(1);
|
||||
}
|
||||
|
||||
void writeEEPROM(void)
|
||||
|
@ -933,7 +933,7 @@ void changeProfile(uint8_t profileIndex)
|
|||
masterConfig.current_profile_index = profileIndex;
|
||||
writeEEPROM();
|
||||
readEEPROM();
|
||||
blinkLedAndSoundBeeper(2, 40, profileIndex + 1);
|
||||
beeperConfirmationBeeps(profileIndex + 1);
|
||||
}
|
||||
|
||||
void changeControlRateProfile(uint8_t profileIndex)
|
||||
|
|
|
@ -30,6 +30,7 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#ifdef GPS
|
||||
#include "io/gps.h"
|
||||
|
@ -38,6 +39,7 @@
|
|||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
||||
#if FLASH_SIZE > 64
|
||||
|
@ -75,7 +77,7 @@ static const uint8_t beep_disarmBeep[] = {
|
|||
};
|
||||
// beeps while stick held in disarm position (after pause)
|
||||
static const uint8_t beep_disarmRepeatBeep[] = {
|
||||
0, 35, 40, 5, BEEPER_COMMAND_STOP
|
||||
0, 100, 10, BEEPER_COMMAND_STOP
|
||||
};
|
||||
// Long beep and pause after that
|
||||
static const uint8_t beep_lowBatteryBeep[] = {
|
||||
|
@ -110,6 +112,11 @@ static const uint8_t beep_2shortBeeps[] = {
|
|||
static const uint8_t beep_2longerBeeps[] = {
|
||||
20, 15, 35, 5, BEEPER_COMMAND_STOP
|
||||
};
|
||||
// 3 beeps
|
||||
static const uint8_t beep_gyroCalibrated[] = {
|
||||
20, 10, 20, 10, 20, 10, BEEPER_COMMAND_STOP
|
||||
};
|
||||
|
||||
// array used for variable # of beeps (reporting GPS sat count, etc)
|
||||
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2];
|
||||
|
||||
|
@ -145,21 +152,22 @@ typedef struct beeperTableEntry_s {
|
|||
#endif
|
||||
|
||||
static const beeperTableEntry_t const beeperTable[] = {
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 0, beep_sos, "RX_LOST_LANDING") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST, 1, beep_txLostBeep, "RX_LOST") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARMING, 2, beep_disarmBeep, "DISARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING, 3, beep_armingBeep, "ARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 4, beep_armedGpsFix, "ARMING_GPS_FIX") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 5, beep_critBatteryBeep, "BAT_CRIT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_LOW, 6, beep_lowBatteryBeep, "BAT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_GPS_STATUS, 7, beep_multiBeeps, NULL) },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_SET, 8, beep_shortBeep, "RX_SET") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 9, beep_disarmRepeatBeep, "DISARM_REPEAT") },
|
||||
{ BEEPER_ENTRY(BEEPER_GYRO_CALIBRATED, 0, beep_gyroCalibrated, "GYRO_CALIBRATED") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 1, beep_sos, "RX_LOST_LANDING") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST, 2, beep_txLostBeep, "RX_LOST") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARMING, 3, beep_disarmBeep, "DISARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING, 4, beep_armingBeep, "ARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 5, beep_armedGpsFix, "ARMING_GPS_FIX") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 6, beep_critBatteryBeep, "BAT_CRIT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_LOW, 7, beep_lowBatteryBeep, "BAT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_GPS_STATUS, 8, beep_multiBeeps, NULL) },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_SET, 9, beep_shortBeep, "RX_SET") },
|
||||
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION, 10, beep_2shortBeeps, "ACC_CALIBRATION") },
|
||||
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION_FAIL, 11, beep_2longerBeeps, "ACC_CALIBRATION_FAIL") },
|
||||
{ BEEPER_ENTRY(BEEPER_READY_BEEP, 12, beep_readyBeep, "READY_BEEP") },
|
||||
{ BEEPER_ENTRY(BEEPER_MULTI_BEEPS, 13, beep_multiBeeps, NULL) }, // FIXME having this listed makes no sense since the beep array will not be initialised.
|
||||
{ BEEPER_ENTRY(BEEPER_ARMED, 14, beep_armedBeep, "ARMED") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 14, beep_disarmRepeatBeep, "DISARM_REPEAT") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMED, 15, beep_armedBeep, "ARMED") },
|
||||
};
|
||||
|
||||
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||
|
@ -209,6 +217,10 @@ void beeper(beeperMode_e mode)
|
|||
void beeperSilence(void)
|
||||
{
|
||||
BEEP_OFF;
|
||||
warningLedDisable();
|
||||
warningLedRefresh();
|
||||
|
||||
|
||||
beeperIsOn = 0;
|
||||
|
||||
beeperNextToggleTime = 0;
|
||||
|
@ -291,7 +303,9 @@ void beeperUpdate(void)
|
|||
beeperIsOn = 1;
|
||||
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
||||
BEEP_ON;
|
||||
//if this was arming beep then mark time (for blackbox)
|
||||
warningLedEnable();
|
||||
warningLedRefresh();
|
||||
// if this was arming beep then mark time (for blackbox)
|
||||
if (
|
||||
beeperPos == 0
|
||||
&& (currentBeeperEntry->mode == BEEPER_ARMING || currentBeeperEntry->mode == BEEPER_ARMING_GPS_FIX)
|
||||
|
@ -303,6 +317,8 @@ void beeperUpdate(void)
|
|||
beeperIsOn = 0;
|
||||
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
||||
BEEP_OFF;
|
||||
warningLedDisable();
|
||||
warningLedRefresh();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -348,7 +364,7 @@ beeperMode_e beeperModeForTableIndex(int idx)
|
|||
*/
|
||||
const char *beeperNameForTableIndex(int idx)
|
||||
{
|
||||
#ifndef BEEPER_NAME
|
||||
#ifndef BEEPER_NAMES
|
||||
UNUSED(idx);
|
||||
return NULL;
|
||||
#else
|
||||
|
|
|
@ -21,6 +21,7 @@ typedef enum {
|
|||
// IMPORTANT: these are in priority order, 0 = Highest
|
||||
BEEPER_SILENCE = 0, // Silence, see beeperSilence()
|
||||
|
||||
BEEPER_GYRO_CALIBRATED,
|
||||
BEEPER_RX_LOST_LANDING, // Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
|
||||
BEEPER_RX_LOST, // Beeps when TX is turned off or signal lost (repeat until TX is okay)
|
||||
BEEPER_DISARMING, // Beep when disarming the board
|
||||
|
|
|
@ -140,23 +140,23 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
|
|||
return;
|
||||
}
|
||||
|
||||
if (isUsingSticksToArm) {
|
||||
// Disarm on throttle down + yaw
|
||||
if (isUsingSticksToArm) {
|
||||
// Disarm on throttle down + yaw
|
||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE) {
|
||||
if (ARMING_FLAG(ARMED)) //board was armed
|
||||
if (ARMING_FLAG(ARMED))
|
||||
mwDisarm();
|
||||
else { //board was not armed
|
||||
beeper(BEEPER_DISARM_REPEAT); //sound tone while stick held
|
||||
rcDelayCommand = 0; //reset so disarm tone will repeat
|
||||
else {
|
||||
beeper(BEEPER_DISARM_REPEAT); // sound tone while stick held
|
||||
rcDelayCommand = 0; // reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
// Disarm on roll (only when retarded_arm is enabled)
|
||||
if (retarded_arm && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO)) {
|
||||
if (ARMING_FLAG(ARMED)) //board was armed
|
||||
if (ARMING_FLAG(ARMED))
|
||||
mwDisarm();
|
||||
else { //board was not armed
|
||||
beeper(BEEPER_DISARM_REPEAT); //sound tone while stick held
|
||||
rcDelayCommand = 0; //reset so disarm tone will repeat
|
||||
else {
|
||||
beeper(BEEPER_DISARM_REPEAT); // sound tone while stick held
|
||||
rcDelayCommand = 0; // reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -27,44 +27,63 @@
|
|||
|
||||
#include "statusindicator.h"
|
||||
|
||||
void blinkLedAndSoundBeeper(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||
{
|
||||
uint8_t i, r;
|
||||
|
||||
for (r = 0; r < repeat; r++) {
|
||||
for (i = 0; i < num; i++) {
|
||||
LED0_TOGGLE; // switch LEDPIN state
|
||||
BEEP_ON;
|
||||
delay(wait);
|
||||
BEEP_OFF;
|
||||
}
|
||||
delay(60);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static uint32_t warningLedTimer = 0;
|
||||
|
||||
void enableWarningLed(uint32_t currentTime)
|
||||
typedef enum {
|
||||
WARNING_LED_OFF = 0,
|
||||
WARNING_LED_ON,
|
||||
WARNING_LED_FLASH
|
||||
} warningLedState_e;
|
||||
|
||||
static warningLedState_e warningLedState = WARNING_LED_OFF;
|
||||
|
||||
void warningLedResetTimer(void) {
|
||||
uint32_t now = millis();
|
||||
warningLedTimer = now + 500000;
|
||||
}
|
||||
|
||||
void warningLedEnable(void)
|
||||
{
|
||||
if (warningLedTimer != 0) {
|
||||
return; // already enabled
|
||||
warningLedState = WARNING_LED_ON;
|
||||
}
|
||||
|
||||
void warningLedDisable(void)
|
||||
{
|
||||
warningLedState = WARNING_LED_OFF;
|
||||
}
|
||||
|
||||
void warningLedFlash(void)
|
||||
{
|
||||
warningLedState = WARNING_LED_FLASH;
|
||||
}
|
||||
|
||||
void warningLedRefresh(void)
|
||||
{
|
||||
switch (warningLedState) {
|
||||
case WARNING_LED_OFF:
|
||||
LED0_OFF;
|
||||
break;
|
||||
case WARNING_LED_ON:
|
||||
LED0_ON;
|
||||
break;
|
||||
case WARNING_LED_FLASH:
|
||||
LED0_TOGGLE;
|
||||
break;
|
||||
}
|
||||
warningLedTimer = currentTime + 500000;
|
||||
LED0_ON;
|
||||
|
||||
uint32_t now = micros();
|
||||
warningLedTimer = now + 500000;
|
||||
}
|
||||
|
||||
void disableWarningLed(void)
|
||||
void warningLedUpdate(void)
|
||||
{
|
||||
warningLedTimer = 0;
|
||||
LED0_OFF;
|
||||
}
|
||||
uint32_t now = micros();
|
||||
|
||||
void updateWarningLed(uint32_t currentTime)
|
||||
{
|
||||
if (warningLedTimer && (int32_t)(currentTime - warningLedTimer) >= 0) {
|
||||
LED0_TOGGLE;
|
||||
warningLedTimer = warningLedTimer + 500000;
|
||||
if ((int32_t)(now - warningLedTimer) < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
warningLedRefresh();
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -17,8 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void blinkLedAndSoundBeeper(uint8_t num, uint8_t wait, uint8_t repeat);
|
||||
|
||||
void enableWarningLed(uint32_t currentTime);
|
||||
void disableWarningLed(void);
|
||||
void updateWarningLed(uint32_t currentTime);
|
||||
void warningLedEnable(void);
|
||||
void warningLedDisable(void);
|
||||
void warningLedRefresh(void);
|
||||
void warningLedUpdate(void);
|
||||
void warningLedFlash(void);
|
||||
|
|
|
@ -276,11 +276,6 @@ void annexCode(void)
|
|||
ENABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
if (isCalibrating()) {
|
||||
LED0_TOGGLE;
|
||||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
if (!STATE(SMALL_ANGLE)) {
|
||||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
@ -289,13 +284,18 @@ void annexCode(void)
|
|||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||
disableWarningLed();
|
||||
if (isCalibrating()) {
|
||||
warningLedFlash();
|
||||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
} else {
|
||||
enableWarningLed(currentTime);
|
||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||
warningLedDisable();
|
||||
} else {
|
||||
warningLedFlash();
|
||||
}
|
||||
}
|
||||
|
||||
updateWarningLed(currentTime);
|
||||
warningLedUpdate();
|
||||
}
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
@ -388,7 +388,7 @@ void mwArm(void)
|
|||
}
|
||||
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
blinkLedAndSoundBeeper(2, 255, 1);
|
||||
beeperConfirmationBeeps(1);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/statusindicator.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
||||
|
@ -95,10 +96,14 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho
|
|||
return;
|
||||
}
|
||||
gyroZero[axis] = (g[axis] + (CALIBRATING_GYRO_CYCLES / 2)) / CALIBRATING_GYRO_CYCLES;
|
||||
blinkLedAndSoundBeeper(10, 15, 1);
|
||||
}
|
||||
}
|
||||
|
||||
if (isOnFinalGyroCalibrationCycle()) {
|
||||
beeper(BEEPER_GYRO_CALIBRATED);
|
||||
}
|
||||
calibratingG--;
|
||||
|
||||
}
|
||||
|
||||
static void applyGyroZero(void)
|
||||
|
|
Loading…
Reference in New Issue