2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
23 #include "common/time.h"
25 #define BEEPER_GET_FLAG(mode) (1 << (mode - 1))
28 #define DSHOT_BEACON_GUARD_DELAY_US 1200000 // Time to separate dshot beacon and armining/disarming events
29 // to prevent interference with motor direction commands
33 // IMPORTANT: the order of the elements should be preserved for backwards compatibility with the configurator.
34 BEEPER_SILENCE
= 0, // Silence, see beeperSilence()
36 BEEPER_GYRO_CALIBRATED
,
37 BEEPER_RX_LOST
, // Beeps when TX is turned off or signal lost (repeat until TX is okay)
38 BEEPER_RX_LOST_LANDING
, // Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
39 BEEPER_DISARMING
, // Beep when disarming the board
40 BEEPER_ARMING
, // Beep when arming the board
41 BEEPER_ARMING_GPS_FIX
, // Beep a special tone when arming the board and GPS has fix
42 BEEPER_BAT_CRIT_LOW
, // Longer warning beeps when battery is critically low (repeats)
43 BEEPER_BAT_LOW
, // Warning beeps when battery is getting low (repeats)
44 BEEPER_GPS_STATUS
, // Use the number of beeps to indicate how many GPS satellites were found
45 BEEPER_RX_SET
, // Beeps when aux channel is set for beep
46 BEEPER_ACC_CALIBRATION
, // ACC inflight calibration completed confirmation
47 BEEPER_ACC_CALIBRATION_FAIL
, // ACC inflight calibration failed
48 BEEPER_READY_BEEP
, // Ring a tone when GPS is locked and ready
49 BEEPER_MULTI_BEEPS
, // Internal value used by 'beeperConfirmationBeeps()'.
50 BEEPER_DISARM_REPEAT
, // Beeps sounded while stick held in disarm position
51 BEEPER_ARMED
, // Warning beeps when board is armed with motors off when idle (repeats until board is disarmed or throttle is increased)
52 BEEPER_SYSTEM_INIT
, // Initialisation beeps when board is powered on
53 BEEPER_USB
, // Some boards have beeper powered USB connected
54 BEEPER_BLACKBOX_ERASE
, // Beep when blackbox erase completes
55 BEEPER_CRASH_FLIP_MODE
, // Crash flip mode is active
56 BEEPER_CAM_CONNECTION_OPEN
, // When the 5 key simulation stated
57 BEEPER_CAM_CONNECTION_CLOSE
, // When the 5 key simulation stop
58 BEEPER_RC_SMOOTHING_INIT_FAIL
, // Warning beep pattern when armed and rc smoothing has not initialized filters
59 BEEPER_ARMING_GPS_NO_FIX
, // Beep a special tone when arming the board and GPS has no fix
60 BEEPER_ALL
, // Turn ON or OFF all beeper conditions
61 // BEEPER_ALL must remain at the bottom of this enum
65 #define BEEPER_ALLOWED_MODES ( \
66 BEEPER_GET_FLAG(BEEPER_GYRO_CALIBRATED) \
67 | BEEPER_GET_FLAG(BEEPER_RX_LOST) \
68 | BEEPER_GET_FLAG(BEEPER_RX_LOST_LANDING) \
69 | BEEPER_GET_FLAG(BEEPER_DISARMING) \
70 | BEEPER_GET_FLAG(BEEPER_ARMING) \
71 | BEEPER_GET_FLAG(BEEPER_ARMING_GPS_FIX) \
72 | BEEPER_GET_FLAG(BEEPER_BAT_CRIT_LOW) \
73 | BEEPER_GET_FLAG(BEEPER_BAT_LOW) \
74 | BEEPER_GET_FLAG(BEEPER_GPS_STATUS) \
75 | BEEPER_GET_FLAG(BEEPER_RX_SET) \
76 | BEEPER_GET_FLAG(BEEPER_ACC_CALIBRATION) \
77 | BEEPER_GET_FLAG(BEEPER_ACC_CALIBRATION_FAIL) \
78 | BEEPER_GET_FLAG(BEEPER_READY_BEEP) \
79 | BEEPER_GET_FLAG(BEEPER_MULTI_BEEPS) \
80 | BEEPER_GET_FLAG(BEEPER_DISARM_REPEAT) \
81 | BEEPER_GET_FLAG(BEEPER_ARMED) \
82 | BEEPER_GET_FLAG(BEEPER_SYSTEM_INIT) \
83 | BEEPER_GET_FLAG(BEEPER_USB) \
84 | BEEPER_GET_FLAG(BEEPER_BLACKBOX_ERASE) \
85 | BEEPER_GET_FLAG(BEEPER_CRASH_FLIP_MODE) \
86 | BEEPER_GET_FLAG(BEEPER_CAM_CONNECTION_OPEN) \
87 | BEEPER_GET_FLAG(BEEPER_CAM_CONNECTION_CLOSE) \
88 | BEEPER_GET_FLAG(BEEPER_RC_SMOOTHING_INIT_FAIL) \
89 | BEEPER_GET_FLAG(BEEPER_ARMING_GPS_NO_FIX) \
92 #define DSHOT_BEACON_ALLOWED_MODES ( \
93 BEEPER_GET_FLAG(BEEPER_RX_LOST) \
94 | BEEPER_GET_FLAG(BEEPER_RX_SET) )
96 void beeper(beeperMode_e mode
);
97 void beeperSilence(void);
98 void beeperUpdate(timeUs_t currentTimeUs
);
99 void beeperConfirmationBeeps(uint8_t beepCount
);
100 void beeperWarningBeeps(uint8_t beepCount
);
101 uint32_t getArmingBeepTimeMicros(void);
102 beeperMode_e
beeperModeForTableIndex(int idx
);
103 uint32_t beeperModeMaskForTableIndex(int idx
);
104 const char *beeperNameForTableIndex(int idx
);
105 int beeperTableEntryCount(void);
106 bool isBeeperOn(void);
107 timeUs_t
getLastDshotBeaconCommandTimeUs(void);