constrain fastA2I to [0-9] (vice [0-9A])
[inav.git] / src / main / io / beeper.c
blob57cba56a61587c32b91f6b329a57f9c89635f90f
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include "stdbool.h"
19 #include "stdint.h"
20 #include "stdlib.h"
22 #include "platform.h"
24 #include "common/utils.h"
26 #include "drivers/sound_beeper.h"
27 #include "drivers/time.h"
29 #include "sensors/battery.h"
30 #include "sensors/sensors.h"
31 #include "sensors/diagnostics.h"
33 #include "rx/rx.h"
35 #include "io/statusindicator.h"
37 #ifdef USE_GPS
38 #include "io/gps.h"
39 #endif
41 #include "fc/config.h"
42 #include "fc/rc_controls.h"
43 #include "fc/rc_modes.h"
44 #include "fc/runtime_config.h"
46 #include "config/feature.h"
48 #ifdef USE_DSHOT
49 #include "drivers/pwm_output.h"
50 #include "fc/fc_core.h"
51 #include "flight/mixer.h"
52 static timeUs_t lastDshotBeeperCommandTimeUs;
53 #endif
55 #include "io/beeper.h"
57 #define MAX_MULTI_BEEPS 20 //size limit for 'beep_multiBeeps[]'
59 #define BEEPER_COMMAND_REPEAT 0xFE
60 #define BEEPER_COMMAND_STOP 0xFF
62 /* Beeper Sound Sequences: (Square wave generation)
63 * Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
64 * start when 0xFF stops the sound when it's completed.
66 * "Sound" Sequences are made so that 1st, 3rd, 5th.. are the delays how
67 * long the beeper is on and 2nd, 4th, 6th.. are the delays how long beeper
68 * is off. Delays are in milliseconds/10 (i.e., 5 => 50ms).
70 // short fast beep
71 static const uint8_t beep_shortBeep[] = {
72 10, 10, BEEPER_COMMAND_STOP
74 // arming beep
75 static const uint8_t beep_armingBeep[] = {
76 30, 5, 5, 5, BEEPER_COMMAND_STOP
78 // armed beep (first pause, then short beep)
79 static const uint8_t beep_armedBeep[] = {
80 0, 245, 10, 5, BEEPER_COMMAND_STOP
82 // disarming beeps
83 static const uint8_t beep_disarmBeep[] = {
84 15, 5, 15, 5, BEEPER_COMMAND_STOP
86 // beeps while stick held in disarm position (after pause)
87 static const uint8_t beep_disarmRepeatBeep[] = {
88 0, 100, 10, BEEPER_COMMAND_STOP
90 // Long beep and pause after that
91 static const uint8_t beep_lowBatteryBeep[] = {
92 25, 50, BEEPER_COMMAND_STOP
94 // critical battery beep
95 static const uint8_t beep_critBatteryBeep[] = {
96 50, 2, BEEPER_COMMAND_STOP
99 // transmitter-signal-lost tone
100 static const uint8_t beep_txLostBeep[] = {
101 50, 50, BEEPER_COMMAND_STOP
103 // SOS morse code:
104 static const uint8_t beep_sos[] = {
105 10, 10, 10, 10, 10, 40, 40, 10, 40, 10, 40, 40, 10, 10, 10, 10, 10, 70, BEEPER_COMMAND_STOP
107 // Arming when GPS is fixed
108 static const uint8_t beep_armedGpsFix[] = {
109 5, 5, 15, 5, 5, 5, 15, 30, BEEPER_COMMAND_STOP
111 // Ready beeps. When gps has fix and copter is ready to fly.
112 static const uint8_t beep_readyBeep[] = {
113 4, 5, 4, 5, 8, 5, 15, 5, 8, 5, 4, 5, 4, 5, BEEPER_COMMAND_STOP
115 // 2 fast short beeps
116 static const uint8_t beep_2shortBeeps[] = {
117 5, 5, 5, 5, BEEPER_COMMAND_STOP
119 // 2 longer beeps
120 static const uint8_t beep_2longerBeeps[] = {
121 20, 15, 35, 5, BEEPER_COMMAND_STOP
123 // 3 beeps
124 static const uint8_t beep_runtimeCalibrationDone[] = {
125 20, 10, 20, 10, 20, 10, BEEPER_COMMAND_STOP
127 // two short beeps and a pause (first pause, then short beep)
128 static const uint8_t beep_launchModeBeep[] = {
129 5, 5, 5, 100, BEEPER_COMMAND_STOP
131 // Two short beeps, then one shorter beep. Beeps to show the throttle needs to be raised. Will repeat every second while the throttle is low.
132 static const uint8_t beep_launchModeLowThrottleBeep[] = {
133 5, 5, 5, 5, 3, 100, BEEPER_COMMAND_STOP
135 // 4 short beeps and a pause. Warning motor about to start at idle throttle
136 static const uint8_t beep_launchModeIdleStartBeep[] = {
137 5, 5, 5, 5, 5, 5, 5, 80, BEEPER_COMMAND_STOP
139 // short beeps
140 static const uint8_t beep_hardwareFailure[] = {
141 10, 10, BEEPER_COMMAND_STOP
143 // Cam connection opened
144 static const uint8_t beep_camOpenBeep[] = {
145 5, 15, 10, 15, 20, BEEPER_COMMAND_STOP
147 // Cam connection close
148 static const uint8_t beep_camCloseBeep[] = {
149 10, 8, 5, BEEPER_COMMAND_STOP
153 // array used for variable # of beeps (reporting GPS sat count, etc)
154 static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2];
156 #define BEEPER_CONFIRMATION_BEEP_DURATION 2
157 #define BEEPER_CONFIRMATION_BEEP_GAP_DURATION 20
160 // Beeper off = false Beeper on = true
161 static bool beeperIsOn = false;
163 // Place in current sequence
164 static uint16_t beeperPos = 0;
165 // Time when beeper routine must act next time
166 static uint32_t beeperNextToggleTime = 0;
167 // Time of last arming beep in microseconds (for blackbox)
168 static uint32_t armingBeepTimeMicros = 0;
170 static void beeperProcessCommand(void);
172 typedef struct beeperTableEntry_s {
173 uint8_t mode;
174 uint8_t priority; // 0 = Highest
175 const uint8_t *sequence;
176 const char *name;
177 } beeperTableEntry_t;
179 #define BEEPER_ENTRY(a,b,c,d) a,b,c,d
181 /*static*/ const beeperTableEntry_t beeperTable[] = {
182 { BEEPER_ENTRY(BEEPER_RUNTIME_CALIBRATION_DONE, 0, beep_runtimeCalibrationDone, "RUNTIME_CALIBRATION") },
183 { BEEPER_ENTRY(BEEPER_HARDWARE_FAILURE , 1, beep_hardwareFailure, "HW_FAILURE") },
184 { BEEPER_ENTRY(BEEPER_RX_LOST, 2, beep_txLostBeep, "RX_LOST") },
185 { BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 3, beep_sos, "RX_LOST_LANDING") },
186 { BEEPER_ENTRY(BEEPER_DISARMING, 4, beep_disarmBeep, "DISARMING") },
187 { BEEPER_ENTRY(BEEPER_ARMING, 5, beep_armingBeep, "ARMING") },
188 { BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 6, beep_armedGpsFix, "ARMING_GPS_FIX") },
189 { BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 7, beep_critBatteryBeep, "BAT_CRIT_LOW") },
190 { BEEPER_ENTRY(BEEPER_BAT_LOW, 8, beep_lowBatteryBeep, "BAT_LOW") },
191 { BEEPER_ENTRY(BEEPER_GPS_STATUS, 9, beep_multiBeeps, "GPS_STATUS") },
192 { BEEPER_ENTRY(BEEPER_RX_SET, 10, beep_shortBeep, "RX_SET") },
193 { BEEPER_ENTRY(BEEPER_ACTION_SUCCESS, 11, beep_2shortBeeps, "ACTION_SUCCESS") },
194 { BEEPER_ENTRY(BEEPER_ACTION_FAIL, 12, beep_2longerBeeps, "ACTION_FAIL") },
195 { BEEPER_ENTRY(BEEPER_READY_BEEP, 13, beep_readyBeep, "READY_BEEP") },
196 { BEEPER_ENTRY(BEEPER_MULTI_BEEPS, 14, beep_multiBeeps, "MULTI_BEEPS") }, // FIXME having this listed makes no sense since the beep array will not be initialised.
197 { BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 15, beep_disarmRepeatBeep, "DISARM_REPEAT") },
198 { BEEPER_ENTRY(BEEPER_ARMED, 16, beep_armedBeep, "ARMED") },
199 { BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 17, NULL, "SYSTEM_INIT") },
200 { BEEPER_ENTRY(BEEPER_USB, 18, NULL, "ON_USB") },
201 { BEEPER_ENTRY(BEEPER_LAUNCH_MODE_ENABLED, 19, beep_launchModeBeep, "LAUNCH_MODE") },
202 { BEEPER_ENTRY(BEEPER_LAUNCH_MODE_LOW_THROTTLE, 20, beep_launchModeLowThrottleBeep, "LAUNCH_MODE_LOW_THROTTLE") },
203 { BEEPER_ENTRY(BEEPER_LAUNCH_MODE_IDLE_START, 21, beep_launchModeIdleStartBeep, "LAUNCH_MODE_IDLE_START") },
204 { BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 22, beep_camOpenBeep, "CAM_CONNECTION_OPEN") },
205 { BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 23, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") },
207 { BEEPER_ENTRY(BEEPER_ALL, 24, NULL, "ALL") },
208 { BEEPER_ENTRY(BEEPER_PREFERENCE, 25, NULL, "PREFERED") },
211 static const beeperTableEntry_t *currentBeeperEntry = NULL;
213 #define BEEPER_TABLE_ENTRY_COUNT (sizeof(beeperTable) / sizeof(beeperTableEntry_t))
216 * Called to activate/deactivate beeper, using the given "BEEPER_..." value.
217 * This function returns immediately (does not block).
219 void beeper(beeperMode_e mode)
221 if (mode == BEEPER_SILENCE || ((getBeeperOffMask() & (1 << (BEEPER_USB-1))) && (feature(FEATURE_VBAT) && (getBatteryCellCount() < 2)))) {
222 beeperSilence();
223 return;
226 const beeperTableEntry_t *selectedCandidate = NULL;
227 for (uint32_t i = 0; i < BEEPER_TABLE_ENTRY_COUNT; i++) {
228 const beeperTableEntry_t *candidate = &beeperTable[i];
229 if (candidate->mode != mode) {
230 continue;
233 if (!currentBeeperEntry) {
234 selectedCandidate = candidate;
235 break;
238 if (candidate->priority < currentBeeperEntry->priority) {
239 selectedCandidate = candidate;
242 break;
245 if (!selectedCandidate) {
246 return;
249 currentBeeperEntry = selectedCandidate;
251 beeperPos = 0;
252 beeperNextToggleTime = 0;
255 void beeperSilence(void)
257 BEEP_OFF;
258 warningLedDisable();
259 warningLedRefresh();
262 beeperIsOn = false;
264 beeperNextToggleTime = 0;
265 beeperPos = 0;
267 currentBeeperEntry = NULL;
270 * Emits the given number of 20ms beeps (with 200ms spacing).
271 * This function returns immediately (does not block).
273 void beeperConfirmationBeeps(uint8_t beepCount)
275 int i;
276 int cLimit;
278 i = 0;
279 cLimit = beepCount * 2;
280 if (cLimit > MAX_MULTI_BEEPS)
281 cLimit = MAX_MULTI_BEEPS; //stay within array size
282 do {
283 beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_DURATION; // 20ms beep
284 beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_GAP_DURATION; // 200ms pause
285 } while (i < cLimit);
286 beep_multiBeeps[i] = BEEPER_COMMAND_STOP; //sequence end
287 beeper(BEEPER_MULTI_BEEPS); //initiate sequence
290 #ifdef USE_GPS
291 void beeperGpsStatus(void)
293 // if GPS fix then beep out number of satellites
294 if (STATE(GPS_FIX) && gpsSol.numSat >= 5) {
295 uint8_t i = 0;
296 do {
297 beep_multiBeeps[i++] = 5;
298 beep_multiBeeps[i++] = 10;
299 } while (i < MAX_MULTI_BEEPS && gpsSol.numSat > i / 2);
301 beep_multiBeeps[i-1] = 50; // extend last pause
302 beep_multiBeeps[i] = BEEPER_COMMAND_STOP;
304 beeper(BEEPER_MULTI_BEEPS); //initiate sequence
305 } else {
306 beeper(BEEPER_RX_SET);
309 #endif
312 * Beeper handler function to be called periodically in loop. Updates beeper
313 * state via time schedule.
315 void beeperUpdate(timeUs_t currentTimeUs)
317 // If beeper option from AUX switch has been selected
318 if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) {
319 #ifdef USE_GPS
320 if (feature(FEATURE_GPS)) {
321 beeperGpsStatus();
322 } else {
323 beeper(BEEPER_RX_SET);
325 #else
326 beeper(BEEPER_RX_SET);
327 #endif
330 // Beep out hardware failure
331 if (!isHardwareHealthy()) {
332 beeper(BEEPER_HARDWARE_FAILURE);
335 // Beeper routine doesn't need to update if there aren't any sounds ongoing
336 if (currentBeeperEntry == NULL) {
337 return;
340 const timeMs_t now = currentTimeUs / 1000;
341 if (beeperNextToggleTime > now) {
342 return;
345 if (!beeperIsOn) {
346 #ifdef USE_DSHOT
347 if (isMotorProtocolDshot() && !areMotorsRunning() && beeperConfig()->dshot_beeper_enabled
348 && currentTimeUs - lastDshotBeeperCommandTimeUs > getDShotBeaconGuardDelayUs())
350 lastDshotBeeperCommandTimeUs = currentTimeUs;
351 sendDShotCommand(beeperConfig()->dshot_beeper_tone);
353 #endif
355 beeperIsOn = true;
356 if (currentBeeperEntry->sequence[beeperPos] != 0) {
357 if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1))))
358 BEEP_ON;
360 warningLedEnable();
361 warningLedRefresh();
362 // if this was arming beep then mark time (for blackbox)
363 if (
364 beeperPos == 0
365 && (currentBeeperEntry->mode == BEEPER_ARMING || currentBeeperEntry->mode == BEEPER_ARMING_GPS_FIX)
367 armingBeepTimeMicros = currentTimeUs;
370 } else {
371 beeperIsOn = false;
372 if (currentBeeperEntry->sequence[beeperPos] != 0) {
373 BEEP_OFF;
374 warningLedDisable();
375 warningLedRefresh();
379 beeperProcessCommand();
383 * Calculates array position when next to change beeper state is due.
385 static void beeperProcessCommand(void)
387 if (currentBeeperEntry->sequence[beeperPos] == BEEPER_COMMAND_REPEAT) {
388 beeperPos = 0;
389 } else if (currentBeeperEntry->sequence[beeperPos] == BEEPER_COMMAND_STOP) {
390 beeperSilence();
391 } else {
392 // Otherwise advance the sequence and calculate next toggle time
393 beeperNextToggleTime = millis() + 10 * currentBeeperEntry->sequence[beeperPos];
394 beeperPos++;
399 * Returns the time that the last arming beep occurred (in system-uptime
400 * microseconds). This is fetched and logged by blackbox.
402 uint32_t getArmingBeepTimeMicros(void)
404 return armingBeepTimeMicros;
408 * Returns the 'beeperMode_e' value for the given beeper-table index,
409 * or BEEPER_SILENCE if none.
411 beeperMode_e beeperModeForTableIndex(int idx)
413 return (idx >= 0 && idx < (int)BEEPER_TABLE_ENTRY_COUNT) ? beeperTable[idx].mode : BEEPER_SILENCE;
417 * Returns the name for the given beeper-table index, or NULL if none.
419 const char *beeperNameForTableIndex(int idx)
421 return (idx >= 0 && idx < (int)BEEPER_TABLE_ENTRY_COUNT) ? beeperTable[idx].name : NULL;
425 * Returns the number of entries in the beeper-sounds table.
427 int beeperTableEntryCount(void)
429 return (int)BEEPER_TABLE_ENTRY_COUNT;
432 #ifdef USE_DSHOT
433 timeUs_t getDShotBeaconGuardDelayUs(void) {
434 // Based on Digital_Cmd_Spec.txt - all delays have 100ms added to ensure that the minimum time has passed.
435 switch (beeperConfig()->dshot_beeper_tone) {
436 case 1:
437 case 2:
438 return 260000 + 100000;
439 case 3:
440 case 4:
441 return 280000 + 100000;
442 case 5:
443 default:
444 return 1020000 + 100000;
448 timeUs_t getLastDshotBeeperCommandTimeUs(void)
450 return lastDshotBeeperCommandTimeUs;
452 #endif