Port of refactored beeper code 181_1
This the "Port of refactored beeper code #669" modification applied to version 1.8.1 (4/4/2015) of the code.
This commit is contained in:
parent
988ae2d503
commit
f02d7403af
|
@ -1,11 +1,18 @@
|
|||
# Buzzer
|
||||
|
||||
Cleanflight supports a buzzer which is used for the following purposes, and more:
|
||||
Cleanflight supports a buzzer which is used for the following purposes:
|
||||
|
||||
* Low Battery alarm (when battery monitoring enabled)
|
||||
* Notification of calibration complete status.
|
||||
* AUX operated beeping - useful for locating your aircraft after a crash.
|
||||
* Failsafe status.
|
||||
* Low and critical battery alarms (when battery monitoring enabled)
|
||||
* Arm/disarm tones (and warning beeps while armed)
|
||||
* Notification of calibration complete status
|
||||
* TX-AUX operated beeping - useful for locating your aircraft after a crash
|
||||
* Failsafe status
|
||||
* Flight mode change
|
||||
* Rate profile change (via TX-AUX switch)
|
||||
|
||||
If the arm/disarm is via the control stick, holding the stick in the disarm position will sound a repeating tone. This can be used as a lost-model locator.
|
||||
|
||||
There is a special arming tone used if a GPS fix has been attained, and there's a "ready" tone sounded after a GPS fix has been attained (only happens once). The tone sounded via the TX-AUX-switch will count out the number of satellites (if GPS fix).
|
||||
|
||||
Buzzer is enabled by default on platforms that have buzzer connections.
|
||||
|
||||
|
|
|
@ -38,7 +38,6 @@
|
|||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
@ -981,22 +980,15 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
|||
}
|
||||
}
|
||||
|
||||
// Beep the buzzer and write the current time to the log as a synchronization point
|
||||
static void blackboxPlaySyncBeep()
|
||||
// Write the time of the last arming beep to the log as a synchronization point
|
||||
static void blackboxLogArmingBeep()
|
||||
{
|
||||
flightLogEvent_syncBeep_t eventData;
|
||||
|
||||
eventData.time = micros();
|
||||
|
||||
/*
|
||||
* The regular beep routines aren't going to work for us, because they queue up the beep to be executed later.
|
||||
* Our beep is timing sensitive, so start beeping now without setting the beeperIsOn flag.
|
||||
*/
|
||||
BEEP_ON;
|
||||
|
||||
// Have the regular beeper code turn off the beep for us eventually, since that's not timing-sensitive
|
||||
queueConfirmationBeep(1);
|
||||
// Get time of last arming beep (in system-uptime microseconds)
|
||||
eventData.time = getArmingBeepTimeMicros();
|
||||
|
||||
// Write the time to the log
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP, (flightLogEventData_t *) &eventData);
|
||||
}
|
||||
|
||||
|
@ -1064,7 +1056,7 @@ void handleBlackbox(void)
|
|||
case BLACKBOX_STATE_PRERUN:
|
||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||
|
||||
blackboxPlaySyncBeep();
|
||||
blackboxLogArmingBeep();
|
||||
break;
|
||||
case BLACKBOX_STATE_RUNNING:
|
||||
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
uint8_t armingFlags = 0;
|
||||
uint8_t stateFlags = 0;
|
||||
|
@ -26,6 +27,34 @@ uint16_t flightModeFlags = 0;
|
|||
|
||||
static uint32_t enabledSensors = 0;
|
||||
|
||||
/**
|
||||
* Enables the given flight mode. A beep is sounded if the flight mode
|
||||
* has changed. Returns the new 'flightModeFlags' value.
|
||||
*/
|
||||
uint16_t enableFlightMode(flightModeFlags_e mask)
|
||||
{
|
||||
uint16_t oldVal = flightModeFlags;
|
||||
|
||||
flightModeFlags |= (mask);
|
||||
if (flightModeFlags != oldVal)
|
||||
queueConfirmationBeep(1);
|
||||
return flightModeFlags;
|
||||
}
|
||||
|
||||
/**
|
||||
* Disables the given flight mode. A beep is sounded if the flight mode
|
||||
* has changed. Returns the new 'flightModeFlags' value.
|
||||
*/
|
||||
uint16_t disableFlightMode(flightModeFlags_e mask)
|
||||
{
|
||||
uint16_t oldVal = flightModeFlags;
|
||||
|
||||
flightModeFlags &= ~(mask);
|
||||
if (flightModeFlags != oldVal)
|
||||
queueConfirmationBeep(1);
|
||||
return flightModeFlags;
|
||||
}
|
||||
|
||||
bool sensors(uint32_t mask)
|
||||
{
|
||||
return enabledSensors & mask;
|
||||
|
|
|
@ -45,8 +45,8 @@ typedef enum {
|
|||
|
||||
extern uint16_t flightModeFlags;
|
||||
|
||||
#define DISABLE_FLIGHT_MODE(mask) (flightModeFlags &= ~(mask))
|
||||
#define ENABLE_FLIGHT_MODE(mask) (flightModeFlags |= (mask))
|
||||
#define DISABLE_FLIGHT_MODE(mask) disableFlightMode(mask)
|
||||
#define ENABLE_FLIGHT_MODE(mask) enableFlightMode(mask)
|
||||
#define FLIGHT_MODE(mask) (flightModeFlags & (mask))
|
||||
|
||||
typedef enum {
|
||||
|
@ -63,6 +63,8 @@ typedef enum {
|
|||
|
||||
extern uint8_t stateFlags;
|
||||
|
||||
uint16_t enableFlightMode(flightModeFlags_e mask);
|
||||
uint16_t disableFlightMode(flightModeFlags_e mask);
|
||||
|
||||
bool sensors(uint32_t mask);
|
||||
void sensorsSet(uint32_t mask);
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include "common/axis.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
@ -133,11 +134,15 @@ void failsafeUpdateState(void)
|
|||
rcData[i] = rxConfig->midrc; // after specified guard time after RC signal is lost (in 0.1sec)
|
||||
}
|
||||
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
|
||||
// beep SOS tones (armed and TX signal lost; autolanding/autodisarm)
|
||||
beeper(BEEPER_TX_LOST_ARMED);
|
||||
failsafeState.events++;
|
||||
}
|
||||
|
||||
if (failsafeShouldHaveCausedLandingByNow() || !ARMING_FLAG(ARMED)) {
|
||||
mwDisarm();
|
||||
// beep to indicate TX signal lost (repeat until TX is okay)
|
||||
beeper(BEEPER_TX_LOST);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
@ -660,6 +661,7 @@ void updateGpsStateForHomeAndHoldMode(void)
|
|||
void updateGpsWaypointsAndMode(void)
|
||||
{
|
||||
bool resetNavNow = false;
|
||||
static bool gpsReadyBeepDone = false;
|
||||
|
||||
if (STATE(GPS_FIX) && GPS_numSat >= 5) {
|
||||
|
||||
|
@ -712,6 +714,10 @@ void updateGpsWaypointsAndMode(void)
|
|||
}
|
||||
}
|
||||
}
|
||||
if (!gpsReadyBeepDone) { //if 'ready' beep not yet done
|
||||
beeper(BEEPER_READY_BEEP); //do ready beep now
|
||||
gpsReadyBeepDone = true; //only beep once
|
||||
}
|
||||
} else {
|
||||
if (FLIGHT_MODE(GPS_HOLD_MODE | GPS_HOME_MODE)) {
|
||||
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#include "stdbool.h"
|
||||
#include "stdint.h"
|
||||
#include "stdlib.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
|
@ -30,171 +31,300 @@
|
|||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#ifdef GPS
|
||||
#include "io/gps.h"
|
||||
#endif
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
||||
#define LONG_PAUSE_DURATION_MILLIS 200
|
||||
#define DOUBLE_PAUSE_DURATION_MILLIS (LONG_PAUSE_DURATION_MILLIS * 2)
|
||||
#define SHORT_PAUSE_DURATION_MILLIS (LONG_PAUSE_DURATION_MILLIS / 4)
|
||||
#define MEDIUM_PAUSE_DURATION_MILLIS (LONG_PAUSE_DURATION_MILLIS / 2)
|
||||
#define SHORT_CONFIRMATION_BEEP_DURATION_MILLIS (SHORT_PAUSE_DURATION_MILLIS / 2)
|
||||
#define MAX_MULTI_BEEPS 20 //size limit for 'beep_multiBeeps[]'
|
||||
|
||||
static uint8_t beeperIsOn = 0, beepDone = 0;
|
||||
static uint32_t beeperLastToggleTime;
|
||||
static void beep(uint16_t pulseMillis);
|
||||
static void beep_code(char first, char second, char third, char pause);
|
||||
/* Beeper Sound Sequences: (Square wave generation)
|
||||
* Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
|
||||
* start when 0xFF stops the sound when it's completed.
|
||||
* If repeat is used then BEEPER_STOP call must be used for stopping the sound.
|
||||
*
|
||||
* "Sound" Sequences are made so that 1st, 3rd, 5th.. are the delays how
|
||||
* long the beeper is on and 2nd, 4th, 6th.. are the delays how long beeper
|
||||
* is off. Delays are in milliseconds/10 (i.e., 5 => 50ms).
|
||||
*/
|
||||
// short fast beep
|
||||
static const uint8_t beep_shortBeep[] = {
|
||||
10, 10, 0xFF
|
||||
};
|
||||
// arming beep
|
||||
static const uint8_t beep_armingBeep[] = {
|
||||
30, 5, 5, 5, 0xFF
|
||||
};
|
||||
// armed beep (first pause, then short beep)
|
||||
static const uint8_t beep_armedBeep[] = {
|
||||
0, 245, 10, 5, 0xFF
|
||||
};
|
||||
// disarming beeps
|
||||
static const uint8_t beep_disarmBeep[] = {
|
||||
15, 5, 15, 5, 0xFF
|
||||
};
|
||||
// beeps while stick held in disarm position (after pause)
|
||||
static const uint8_t beep_disarmRepeatBeep[] = {
|
||||
0, 35, 40, 5, 0xFF
|
||||
};
|
||||
// Long beep and pause after that
|
||||
static const uint8_t beep_lowBatteryBeep[] = {
|
||||
25, 50, 0xFF
|
||||
};
|
||||
// critical battery beep
|
||||
static const uint8_t beep_critBatteryBeep[] = {
|
||||
50, 2, 0xFF
|
||||
};
|
||||
// single confirmation beep
|
||||
static const uint8_t beep_confirmBeep[] = {
|
||||
2, 20, 0xFF
|
||||
};
|
||||
// transmitter-signal-lost tone
|
||||
static const uint8_t beep_txLostBeep[] = {
|
||||
50, 50, 0xFF
|
||||
};
|
||||
// SOS morse code:
|
||||
static const uint8_t beep_sos[] = {
|
||||
10, 10, 10, 10, 10, 40, 40, 10, 40, 10, 40, 40, 10, 10, 10, 10, 10, 70, 0xFF
|
||||
};
|
||||
// Arming when GPS is fixed
|
||||
static const uint8_t beep_armedGpsFix[] = {
|
||||
5, 5, 15, 5, 5, 5, 15, 30, 0xFF
|
||||
};
|
||||
// Ready beeps. When gps has fix and copter is ready to fly.
|
||||
static const uint8_t beep_readyBeep[] = {
|
||||
4, 5, 4, 5, 8, 5, 15, 5, 8, 5, 4, 5, 4, 5, 0xFF
|
||||
};
|
||||
// 2 fast short beeps
|
||||
static const uint8_t beep_2shortBeeps[] = {
|
||||
5, 5, 5, 5, 0xFF
|
||||
};
|
||||
// 3 fast short beeps
|
||||
static const uint8_t beep_3shortBeeps[] = {
|
||||
5, 5, 5, 5, 5, 5, 0xFF
|
||||
};
|
||||
// array used for variable # of beeps (reporting GPS sat count, etc)
|
||||
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS+2];
|
||||
|
||||
static uint8_t toggleBeep = 0;
|
||||
// Current Beeper mode
|
||||
static uint8_t beeperMode = BEEPER_STOPPED;
|
||||
// Beeper off = 0 Beeper on = 1
|
||||
static uint8_t beeperIsOn = 0;
|
||||
// Pointer to current sequence
|
||||
static const uint8_t *beeperPtr = NULL;
|
||||
// Place in current sequence
|
||||
static uint16_t beeperPos = 0;
|
||||
// Time when beeper routine must act next time
|
||||
static uint32_t beeperNextToggleTime = 0;
|
||||
// Time of last arming beep in microseconds (for blackbox)
|
||||
static uint32_t armingBeepTimeMicros = 0;
|
||||
|
||||
typedef enum {
|
||||
FAILSAFE_IDLE = 0,
|
||||
FAILSAFE_LANDING,
|
||||
FAILSAFE_FIND_ME
|
||||
} failsafeBeeperWarnings_e;
|
||||
static void beeperCalculations(void);
|
||||
|
||||
void beepcodeInit(void)
|
||||
/*
|
||||
* Called to activate/deactive beeper, using the given "BEEPER_..." value.
|
||||
* This function returns immediately (does not block).
|
||||
*/
|
||||
void beeper(uint8_t mode)
|
||||
{
|
||||
#ifdef GPS
|
||||
uint8_t i;
|
||||
#endif
|
||||
|
||||
// Just return if same or higher priority sound is active.
|
||||
if (beeperMode <= mode)
|
||||
return;
|
||||
|
||||
switch (mode) {
|
||||
case BEEPER_STOP:
|
||||
beeperMode = BEEPER_STOPPED;
|
||||
beeperNextToggleTime = millis();
|
||||
BEEP_OFF;
|
||||
beeperIsOn = 0;
|
||||
beeperPtr = NULL;
|
||||
break;
|
||||
case BEEPER_READY_BEEP:
|
||||
beeperPtr = beep_readyBeep;
|
||||
beeperMode = mode;
|
||||
break;
|
||||
case BEEPER_ARMING:
|
||||
beeperPtr = beep_armingBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_DISARMING:
|
||||
beeperPtr = beep_disarmBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_DISARM_REPEAT:
|
||||
beeperPtr = beep_disarmRepeatBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_ACC_CALIBRATION:
|
||||
beeperPtr = beep_2shortBeeps;
|
||||
beeperMode = mode;
|
||||
break;
|
||||
case BEEPER_ACC_CALIBRATION_FAIL:
|
||||
beeperPtr = beep_3shortBeeps;
|
||||
beeperMode = mode;
|
||||
break;
|
||||
case BEEPER_TX_LOST_ARMED:
|
||||
beeperPtr = beep_sos;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_TX_LOST:
|
||||
beeperPtr = beep_txLostBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_BAT_LOW:
|
||||
beeperPtr = beep_lowBatteryBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_BAT_CRIT_LOW:
|
||||
beeperPtr = beep_critBatteryBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_ARMED:
|
||||
beeperPtr = beep_armedBeep;
|
||||
beeperMode = mode;
|
||||
break;
|
||||
case BEEPER_ARMING_GPS_FIX:
|
||||
beeperPtr = beep_armedGpsFix;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_CONFIRM_BEEP:
|
||||
beeperPtr = beep_confirmBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_MULTI_BEEPS:
|
||||
beeperPtr = beep_multiBeeps;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
case BEEPER_TX_SET:
|
||||
#ifdef GPS // if GPS fix then beep out number of satellites
|
||||
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && GPS_numSat >= 5) {
|
||||
i = 0;
|
||||
do {
|
||||
beep_multiBeeps[i++] = 5;
|
||||
beep_multiBeeps[i++] = 10;
|
||||
} while (i < MAX_MULTI_BEEPS && GPS_numSat > i / 2);
|
||||
beep_multiBeeps[i-1] = 50; //extend last pause
|
||||
beep_multiBeeps[i] = 0xFF;
|
||||
beeperPtr = beep_multiBeeps;
|
||||
beeperMode = mode;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
beeperPtr = beep_shortBeep;
|
||||
beeperMode = mode;
|
||||
beeperNextToggleTime = 0;
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
beeperPos = 0;
|
||||
}
|
||||
|
||||
void beepcodeUpdateState(batteryState_e batteryState)
|
||||
/*
|
||||
* Emits the given number of 20ms beeps (with 200ms spacing).
|
||||
* This function returns immediately (does not block).
|
||||
*/
|
||||
void queueConfirmationBeep(uint8_t beepCount)
|
||||
{
|
||||
static uint8_t beeperOnBox;
|
||||
#ifdef GPS
|
||||
static uint8_t warn_noGPSfix = 0;
|
||||
#endif
|
||||
static failsafeBeeperWarnings_e warn_failsafe = FAILSAFE_IDLE;
|
||||
int i;
|
||||
int cLimit;
|
||||
|
||||
//===================== BeeperOn via rcOptions =====================
|
||||
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) { // unconditional beeper on via AUXn switch
|
||||
beeperOnBox = 1;
|
||||
} else {
|
||||
beeperOnBox = 0;
|
||||
if(beepCount <= 1) //if single beep then
|
||||
beeper(BEEPER_CONFIRM_BEEP); //use dedicated array
|
||||
else {
|
||||
i = 0;
|
||||
cLimit = beepCount * 2;
|
||||
if(cLimit > MAX_MULTI_BEEPS)
|
||||
cLimit = MAX_MULTI_BEEPS; //stay within array size
|
||||
do {
|
||||
beep_multiBeeps[i++] = 2; //20ms beep
|
||||
beep_multiBeeps[i++] = 20; //200ms pause
|
||||
} while (i < cLimit);
|
||||
beep_multiBeeps[i] = 0xFF; //sequence end
|
||||
beeper(BEEPER_MULTI_BEEPS); //initiate sequence
|
||||
}
|
||||
//===================== Beeps for failsafe =====================
|
||||
if (feature(FEATURE_FAILSAFE)) {
|
||||
if (failsafeShouldForceLanding(ARMING_FLAG(ARMED))) {
|
||||
warn_failsafe = FAILSAFE_LANDING;
|
||||
}
|
||||
|
||||
if (failsafeShouldHaveCausedLandingByNow()) {
|
||||
warn_failsafe = FAILSAFE_FIND_ME;
|
||||
/*
|
||||
* Beeper handler function to be called periodically in loop. Updates beeper
|
||||
* state via time schedule.
|
||||
*/
|
||||
void beeperUpdate(void)
|
||||
{
|
||||
// If beeper option from AUX switch has been selected
|
||||
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) {
|
||||
if (beeperMode > BEEPER_TX_SET)
|
||||
beeper(BEEPER_TX_SET);
|
||||
}
|
||||
|
||||
// Beeper routine doesn't need to update if there aren't any sounds ongoing
|
||||
if (beeperMode == BEEPER_STOPPED || beeperPtr == NULL)
|
||||
return;
|
||||
|
||||
if (!beeperIsOn && beeperNextToggleTime <= millis()) {
|
||||
beeperIsOn = 1;
|
||||
if (beeperPtr[beeperPos] != 0) {
|
||||
BEEP_ON;
|
||||
//if this was arming beep then mark time (for blackbox)
|
||||
if (beeperPos == 0 && (beeperMode == BEEPER_ARMING ||
|
||||
beeperMode == BEEPER_ARMING_GPS_FIX)) {
|
||||
armingBeepTimeMicros = micros();
|
||||
}
|
||||
}
|
||||
|
||||
if (failsafeHasTimerElapsed() && !ARMING_FLAG(ARMED)) {
|
||||
warn_failsafe = FAILSAFE_FIND_ME;
|
||||
}
|
||||
|
||||
if (failsafeIsIdle()) {
|
||||
warn_failsafe = FAILSAFE_IDLE; // turn off alarm if TX is okay
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef GPS
|
||||
//===================== GPS fix notification handling =====================
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
if ((IS_RC_MODE_ACTIVE(BOXGPSHOME) || IS_RC_MODE_ACTIVE(BOXGPSHOLD)) && !STATE(GPS_FIX)) { // if no fix and gps funtion is activated: do warning beeps
|
||||
warn_noGPSfix = 1;
|
||||
} else {
|
||||
warn_noGPSfix = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
//===================== Priority driven Handling =====================
|
||||
// beepcode(length1,length2,length3,pause)
|
||||
// D: Double, L: Long, M: Middle, S: Short, N: None
|
||||
if (warn_failsafe == 2)
|
||||
beep_code('L','N','N','D'); // failsafe "find me" signal
|
||||
else if (warn_failsafe == 1)
|
||||
beep_code('S','M','L','M'); // failsafe landing active
|
||||
#ifdef GPS
|
||||
else if (warn_noGPSfix == 1)
|
||||
beep_code('S','S','N','M');
|
||||
#endif
|
||||
else if (beeperOnBox == 1)
|
||||
beep_code('S','S','S','M'); // beeperon
|
||||
else if (batteryState == BATTERY_CRITICAL)
|
||||
beep_code('S','S','M','D');
|
||||
else if (batteryState == BATTERY_WARNING)
|
||||
beep_code('S','M','M','D');
|
||||
else if (FLIGHT_MODE(AUTOTUNE_MODE))
|
||||
beep_code('S','M','S','M');
|
||||
else if (toggleBeep > 0)
|
||||
beep(SHORT_CONFIRMATION_BEEP_DURATION_MILLIS); // fast confirmation beep
|
||||
else {
|
||||
beeperCalculations();
|
||||
} else if (beeperIsOn && beeperNextToggleTime <= millis()) {
|
||||
beeperIsOn = 0;
|
||||
BEEP_OFF;
|
||||
}
|
||||
}
|
||||
|
||||
// duration is specified in multiples of SHORT_CONFIRMATION_BEEP_DURATION_MILLIS
|
||||
void queueConfirmationBeep(uint8_t duration) {
|
||||
toggleBeep = duration;
|
||||
}
|
||||
|
||||
void beep_code(char first, char second, char third, char pause)
|
||||
{
|
||||
char patternChar[4];
|
||||
uint16_t Duration;
|
||||
static uint8_t icnt = 0;
|
||||
|
||||
patternChar[0] = first;
|
||||
patternChar[1] = second;
|
||||
patternChar[2] = third;
|
||||
patternChar[3] = pause;
|
||||
switch (patternChar[icnt]) {
|
||||
case 'N':
|
||||
Duration = 0;
|
||||
break;
|
||||
case 'S':
|
||||
Duration = LONG_PAUSE_DURATION_MILLIS / 4;
|
||||
break;
|
||||
case 'M':
|
||||
Duration = LONG_PAUSE_DURATION_MILLIS / 2;
|
||||
break;
|
||||
case 'D':
|
||||
Duration = LONG_PAUSE_DURATION_MILLIS * 2;
|
||||
break;
|
||||
case 'L':
|
||||
default:
|
||||
Duration = LONG_PAUSE_DURATION_MILLIS;
|
||||
break;
|
||||
}
|
||||
|
||||
if (icnt < 3 && Duration != 0)
|
||||
beep(Duration);
|
||||
if (icnt >= 3 && (beeperLastToggleTime < millis() - Duration)) {
|
||||
icnt = 0;
|
||||
toggleBeep = 0;
|
||||
}
|
||||
if (beepDone == 1 || Duration == 0) {
|
||||
if (icnt < 3)
|
||||
icnt++;
|
||||
beepDone = 0;
|
||||
beeperIsOn = 0;
|
||||
BEEP_OFF;
|
||||
}
|
||||
}
|
||||
|
||||
static void beep(uint16_t pulseMillis)
|
||||
{
|
||||
if (beeperIsOn) {
|
||||
if (millis() >= beeperLastToggleTime + pulseMillis) {
|
||||
beeperIsOn = 0;
|
||||
if (beeperPtr[beeperPos] != 0) {
|
||||
BEEP_OFF;
|
||||
beeperLastToggleTime = millis();
|
||||
if (toggleBeep >0)
|
||||
toggleBeep--;
|
||||
beepDone = 1;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (millis() >= (beeperLastToggleTime + LONG_PAUSE_DURATION_MILLIS)) { // Beeper is off and long pause time is up -> turn it on
|
||||
beeperIsOn = 1;
|
||||
BEEP_ON;
|
||||
beeperLastToggleTime = millis(); // save the time the buzer turned on
|
||||
beeperCalculations();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Calculates array position when next to change beeper state is due.
|
||||
*/
|
||||
void beeperCalculations(void)
|
||||
{
|
||||
if (beeperPtr[beeperPos] == 0xFE) {
|
||||
// If sequence is 0xFE then repeat from start
|
||||
beeperPos = 0;
|
||||
} else if (beeperPtr[beeperPos] == 0xFF) {
|
||||
// If sequence is 0xFF then stop
|
||||
beeperMode = BEEPER_STOPPED;
|
||||
BEEP_OFF;
|
||||
beeperIsOn = 0;
|
||||
} else {
|
||||
// Otherwise advance the sequence and calculate next toggle time
|
||||
beeperNextToggleTime = millis() + 10 * beeperPtr[beeperPos];
|
||||
beeperPos++;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Returns the time that the last arming beep occurred (in system-uptime
|
||||
* microseconds). This is fetched and logged by blackbox.
|
||||
*/
|
||||
uint32_t getArmingBeepTimeMicros(void)
|
||||
{
|
||||
return armingBeepTimeMicros;
|
||||
}
|
||||
|
|
|
@ -17,5 +17,45 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void beepcodeUpdateState(batteryState_e batteryState);
|
||||
void queueConfirmationBeep(uint8_t duration);
|
||||
void beeper(uint8_t mode);
|
||||
void beeperUpdate(void);
|
||||
void queueConfirmationBeep(uint8_t beepCount);
|
||||
uint32_t getArmingBeepTimeMicros(void);
|
||||
|
||||
/* Beeper different modes: (lower number is higher priority)
|
||||
* BEEPER_STOP - Stops beeping
|
||||
* BEEPER_TX_LOST_ARMED - Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
|
||||
* BEEPER_TX_LOST - Beeps when TX is turned off or signal lost (repeat until TX is okay)
|
||||
* BEEPER_DISARMING - Beep when disarming the board
|
||||
* BEEPER_ARMING - Beep when arming the board
|
||||
* BEEPER_ARMING_GPS_FIX - Beep a tone when arming the board and GPS has fix
|
||||
* BEEPER_BAT_CRIT_LOW - Faster warning beeps when battery is critically low (repeats)
|
||||
* BEEPER_BAT_LOW - Warning beeps when battery is getting low (repeats)
|
||||
* BEEPER_TX_SET - Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled.
|
||||
* BEEPER_DISARM_REPEAT - Beeps sounded while stick held in disarm position
|
||||
* BEEPER_ACC_CALIBRATION - ACC inflight calibration completed confirmation
|
||||
* BEEPER_ACC_CALIBRATION_FAIL - ACC inflight calibration failed
|
||||
* BEEPER_READY_BEEP - Ring a tone when board is ready to flight (GPS ready).
|
||||
* BEEPER_CONFIRM_BEEP - Single short confirmation beep.
|
||||
* BEEPER_MULTI_BEEPS - Internal value used by 'queueConfirmationBeep()'.
|
||||
* BEEPER_ARMED - Warning beeps when board is armed. (repeats until board is disarmed or throttle is increased)
|
||||
*/
|
||||
enum {
|
||||
BEEPER_STOP = 0, // Highest priority command which is used only for stopping the beeper
|
||||
BEEPER_TX_LOST_ARMED,
|
||||
BEEPER_TX_LOST,
|
||||
BEEPER_DISARMING,
|
||||
BEEPER_ARMING,
|
||||
BEEPER_ARMING_GPS_FIX,
|
||||
BEEPER_BAT_CRIT_LOW,
|
||||
BEEPER_BAT_LOW,
|
||||
BEEPER_TX_SET,
|
||||
BEEPER_DISARM_REPEAT,
|
||||
BEEPER_ACC_CALIBRATION,
|
||||
BEEPER_ACC_CALIBRATION_FAIL,
|
||||
BEEPER_READY_BEEP,
|
||||
BEEPER_CONFIRM_BEEP,
|
||||
BEEPER_MULTI_BEEPS,
|
||||
BEEPER_ARMED,
|
||||
BEEPER_STOPPED // State which is used when beeper is in idle mode
|
||||
};
|
||||
|
|
|
@ -138,18 +138,29 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
|
|||
return;
|
||||
}
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
// actions during armed
|
||||
|
||||
if (isUsingSticksToArm) {
|
||||
// Disarm on throttle down + yaw
|
||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE)
|
||||
mwDisarm();
|
||||
|
||||
// Disarm on roll (only when retarded_arm is enabled)
|
||||
if (retarded_arm && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO))
|
||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE) {
|
||||
if (ARMING_FLAG(ARMED)) //board was armed
|
||||
mwDisarm();
|
||||
else { //board was not armed
|
||||
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
|
||||
mwDisarm();
|
||||
else { //board was not armed
|
||||
beeper(BEEPER_DISARM_REPEAT); //sound tone while stick held
|
||||
rcDelayCommand = 0; //reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
// actions during armed
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -108,7 +108,6 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
|||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMixers);
|
||||
void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfiguration);
|
||||
void rxInit(rxConfig_t *rxConfig);
|
||||
void beepcodeInit(void);
|
||||
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
|
||||
void navigationInit(gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int8_t magHardwareToUse, int16_t magDeclinationFromConfig);
|
||||
|
@ -348,8 +347,6 @@ void init(void)
|
|||
|
||||
failsafeInit(&masterConfig.rxConfig);
|
||||
|
||||
beepcodeInit();
|
||||
|
||||
rxInit(&masterConfig.rxConfig);
|
||||
|
||||
#ifdef GPS
|
||||
|
|
|
@ -243,6 +243,11 @@ void annexCode(void)
|
|||
if (feature(FEATURE_VBAT)) {
|
||||
updateBatteryVoltage();
|
||||
batteryState = calculateBatteryState();
|
||||
//handle beepers for battery levels
|
||||
if (batteryState == BATTERY_CRITICAL)
|
||||
beeper(BEEPER_BAT_CRIT_LOW); //critically low battery
|
||||
else if (batteryState == BATTERY_WARNING)
|
||||
beeper(BEEPER_BAT_LOW); //low battery
|
||||
}
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER)) {
|
||||
|
@ -252,7 +257,7 @@ void annexCode(void)
|
|||
}
|
||||
}
|
||||
|
||||
beepcodeUpdateState(batteryState);
|
||||
beeperUpdate(); //call periodic beeper handler
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
LED0_ON;
|
||||
|
@ -318,6 +323,8 @@ void mwDisarm(void)
|
|||
finishBlackbox();
|
||||
}
|
||||
#endif
|
||||
|
||||
beeper(BEEPER_DISARMING); // emit disarm tone
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -356,6 +363,16 @@ void mwArm(void)
|
|||
#endif
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
|
||||
//beep to indicate arming
|
||||
#ifdef GPS
|
||||
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && GPS_numSat >= 5)
|
||||
beeper(BEEPER_ARMING_GPS_FIX);
|
||||
else
|
||||
beeper(BEEPER_ARMING);
|
||||
#else
|
||||
beeper(BEEPER_ARMING);
|
||||
#endif
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -381,9 +398,9 @@ void handleInflightCalibrationStickPosition(void)
|
|||
} else {
|
||||
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
|
||||
if (AccInflightCalibrationArmed) {
|
||||
queueConfirmationBeep(4);
|
||||
beeper(BEEPER_ACC_CALIBRATION);
|
||||
} else {
|
||||
queueConfirmationBeep(6);
|
||||
beeper(BEEPER_ACC_CALIBRATION_FAIL);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -498,6 +515,8 @@ void executePeriodicTasks(void)
|
|||
|
||||
void processRx(void)
|
||||
{
|
||||
static bool armedBeeperOn = false;
|
||||
|
||||
calculateRxChannelsAndUpdateFailsafe(currentTime);
|
||||
|
||||
// in 3D mode, we need to be able to disarm by switch at any time
|
||||
|
@ -523,17 +542,41 @@ void processRx(void)
|
|||
pidResetErrorAngle();
|
||||
pidResetErrorGyro();
|
||||
}
|
||||
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
|
||||
// When armed and motors aren't spinning, do beeps and then disarm
|
||||
// board after delay so users without buzzer won't lose fingers.
|
||||
// mixTable constrains motor commands, so checking throttleStatus is enough
|
||||
if (ARMING_FLAG(ARMED)
|
||||
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
|
||||
&& masterConfig.auto_disarm_delay != 0
|
||||
&& isUsingSticksForArming()) {
|
||||
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)) {
|
||||
if (isUsingSticksForArming()) {
|
||||
if (throttleStatus == THROTTLE_LOW) { //throttle is low; disarm after delay
|
||||
if (masterConfig.auto_disarm_delay != 0 &&
|
||||
(int32_t)(disarmAt - millis()) < 0) {
|
||||
mwDisarm(); //disarm configured and delay is over
|
||||
armedBeeperOn = false; //track beep status
|
||||
}
|
||||
else { //still armed; do warning beeps while armed
|
||||
beeper(BEEPER_ARMED);
|
||||
armedBeeperOn = true; //track beep status
|
||||
}
|
||||
}
|
||||
else { //throttle is not low
|
||||
if (masterConfig.auto_disarm_delay != 0) //extend disarm time
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay*1000;
|
||||
if (armedBeeperOn) { //if BEEPER_ARMED in progress then
|
||||
beeper(BEEPER_STOP); //stop trailing beep
|
||||
armedBeeperOn = false; //track beep status
|
||||
}
|
||||
}
|
||||
}
|
||||
else { //arming is via AUX switch; beep while throttle low
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
if ((int32_t)(disarmAt - millis()) < 0) // delay is over
|
||||
mwDisarm();
|
||||
} else {
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // extend delay
|
||||
beeper(BEEPER_ARMED);
|
||||
armedBeeperOn = true; //track beep status
|
||||
} else if (armedBeeperOn) { //if BEEPER_ARMED in progress then
|
||||
beeper(BEEPER_STOP); //stop trailing beep
|
||||
armedBeeperOn = false; //track beep status
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -139,7 +139,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
|||
if (InflightcalibratingA == 1) {
|
||||
AccInflightCalibrationActive = false;
|
||||
AccInflightCalibrationMeasurementDone = true;
|
||||
queueConfirmationBeep(5); // beeper to indicating the end of calibration
|
||||
beeper(BEEPER_ACC_CALIBRATION); // indicate end of calibration
|
||||
// recover saved values to maintain current flight behaviour until new values are transferred
|
||||
accelerationTrims->raw[X] = accZero_saved[X];
|
||||
accelerationTrims->raw[Y] = accZero_saved[Y];
|
||||
|
|
|
@ -154,6 +154,16 @@ uint8_t armingFlags;
|
|||
int32_t sonarAlt;
|
||||
|
||||
|
||||
uint16_t enableFlightMode(flightModeFlags_e mask)
|
||||
{
|
||||
return flightModeFlags |= (mask);
|
||||
}
|
||||
|
||||
uint16_t disableFlightMode(flightModeFlags_e mask)
|
||||
{
|
||||
return flightModeFlags &= ~(mask);
|
||||
}
|
||||
|
||||
void gyroUpdate(void) {};
|
||||
bool sensors(uint32_t mask)
|
||||
{
|
||||
|
|
|
@ -90,6 +90,15 @@ int16_t accADC[XYZ_AXIS_COUNT];
|
|||
int16_t gyroADC[XYZ_AXIS_COUNT];
|
||||
|
||||
|
||||
uint16_t enableFlightMode(flightModeFlags_e mask)
|
||||
{
|
||||
return flightModeFlags |= (mask);
|
||||
}
|
||||
|
||||
uint16_t disableFlightMode(flightModeFlags_e mask)
|
||||
{
|
||||
return flightModeFlags &= ~(mask);
|
||||
}
|
||||
|
||||
void gyroUpdate(void) {};
|
||||
bool sensors(uint32_t mask)
|
||||
|
|
|
@ -191,6 +191,10 @@ void queueConfirmationBeep(uint8_t) {
|
|||
callCounts[COUNTER_QUEUE_CONFIRMATION_BEEP]++;
|
||||
}
|
||||
|
||||
void beeper(uint8_t mode) {
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
void changeControlRateProfile(uint8_t) {
|
||||
callCounts[COUNTER_CHANGE_CONTROL_RATE_PROFILE]++;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue