Extend Backpack telemetry forwarding options (#2885)
[ExpressLRS.git] / src / lib / CONFIG / config.h
blob6b251bb614c3534bde4b80e35139adb05777ae43
1 #pragma once
3 #include "targets.h"
4 #include "elrs_eeprom.h"
5 #include "options.h"
6 #include "common.h"
8 #if defined(PLATFORM_ESP32)
9 #include <nvs_flash.h>
10 #include <nvs.h>
11 #endif
13 // CONFIG_MAGIC is ORed with CONFIG_VERSION in the version field
14 #define CONFIG_MAGIC_MASK (0b11U << 30)
15 #define TX_CONFIG_MAGIC (0b01U << 30)
16 #define RX_CONFIG_MAGIC (0b10U << 30)
18 #define TX_CONFIG_VERSION 7U
19 #define RX_CONFIG_VERSION 9U
21 #if defined(TARGET_TX)
23 #define CONFIG_TX_BUTTON_ACTION_CNT 2
24 #define CONFIG_TX_MODEL_CNT 64
26 typedef enum {
27 HT_OFF,
28 HT_ON,
29 HT_AUX1_UP,
30 HT_AUX1_DN,
31 HT_AUX2_UP,
32 HT_AUX2_DN,
33 HT_AUX3_UP,
34 HT_AUX3_DN,
35 HT_AUX4_UP,
36 HT_AUX4_DN,
37 HT_AUX5_UP,
38 HT_AUX5_DN,
39 HT_AUX6_UP,
40 HT_AUX6_DN,
41 HT_AUX7_UP,
42 HT_AUX7_DN,
43 HT_AUX8_UP,
44 HT_AUX8_DN,
45 } headTrackingEnable_t;
47 typedef struct {
48 uint32_t rate:4,
49 tlm:4,
50 power:3,
51 switchMode:2,
52 boostChannel:3, // dynamic power boost AUX channel
53 dynamicPower:1,
54 modelMatch:1,
55 txAntenna:2, // FUTURE: Which TX antenna to use, 0=Auto
56 ptrStartChannel:4,
57 ptrEnableChannel:5,
58 linkMode:3;
59 } model_config_t;
61 typedef struct {
62 uint8_t pressType:1, // 0 short, 1 long
63 count:3, // 1-8 click count for short, .5sec hold count for long
64 action:4; // action to execute
65 } button_action_t;
67 typedef union {
68 struct {
69 uint8_t color; // RRRGGGBB
70 button_action_t actions[CONFIG_TX_BUTTON_ACTION_CNT];
71 uint8_t unused;
72 } val;
73 uint32_t raw;
74 } tx_button_color_t;
76 typedef enum {
77 BACKPACK_TELEM_MODE_OFF,
78 BACKPACK_TELEM_MODE_ESPNOW,
79 BACKPACK_TELEM_MODE_WIFI,
80 BACKPACK_TELEM_MODE_BLUETOOTH,
81 } telem_mode_t;
83 typedef struct {
84 uint32_t version;
85 uint8_t vtxBand; // 0=Off, else band number
86 uint8_t vtxChannel; // 0=Ch1 -> 7=Ch8
87 uint8_t vtxPower; // 0=Do not set, else power number
88 uint8_t vtxPitmode; // Off/On/AUX1^/AUX1v/etc
89 uint8_t powerFanThreshold:4; // Power level to enable fan if present
90 model_config_t model_config[CONFIG_TX_MODEL_CNT];
91 uint8_t fanMode; // some value used by thermal?
92 uint8_t motionMode:2, // bool, but space for 2 more modes
93 dvrStopDelay:3,
94 backpackDisable:1, // bool, disable backpack via EN pin if available
95 backpackTlmMode:2; // 0=Off, 1=Fwd tlm via espnow, 2=fwd tlm via wifi 3=(FUTURE) bluetooth
96 uint8_t dvrStartDelay:3,
97 dvrAux:5;
98 tx_button_color_t buttonColors[2]; // FUTURE: TX RGB color / mode (sets color of TX, can be a static color or standard)
99 // FUTURE: Model RGB color / mode (sets LED color mode on the model, but can be second TX led color too)
100 // FUTURE: Custom button actions
101 } tx_config_t;
103 class TxConfig
105 public:
106 TxConfig();
107 void Load();
108 void Commit();
110 // Getters
111 uint8_t GetRate() const { return m_model->rate; }
112 uint8_t GetTlm() const { return m_model->tlm; }
113 uint8_t GetPower() const { return m_model->power; }
114 bool GetDynamicPower() const { return m_model->dynamicPower; }
115 uint8_t GetBoostChannel() const { return m_model->boostChannel; }
116 uint8_t GetSwitchMode() const { return m_model->switchMode; }
117 uint8_t GetAntennaMode() const { return m_model->txAntenna; }
118 uint8_t GetLinkMode() const { return m_model->linkMode; }
119 bool GetModelMatch() const { return m_model->modelMatch; }
120 bool IsModified() const { return m_modified; }
121 uint8_t GetVtxBand() const { return m_config.vtxBand; }
122 uint8_t GetVtxChannel() const { return m_config.vtxChannel; }
123 uint8_t GetVtxPower() const { return m_config.vtxPower; }
124 uint8_t GetVtxPitmode() const { return m_config.vtxPitmode; }
125 uint8_t GetPowerFanThreshold() const { return m_config.powerFanThreshold; }
126 uint8_t GetFanMode() const { return m_config.fanMode; }
127 uint8_t GetMotionMode() const { return m_config.motionMode; }
128 uint8_t GetDvrAux() const { return m_config.dvrAux; }
129 uint8_t GetDvrStartDelay() const { return m_config.dvrStartDelay; }
130 uint8_t GetDvrStopDelay() const { return m_config.dvrStopDelay; }
131 bool GetBackpackDisable() const { return m_config.backpackDisable; }
132 uint8_t GetBackpackTlmMode() const { return m_config.backpackTlmMode; }
133 tx_button_color_t const *GetButtonActions(uint8_t button) const { return &m_config.buttonColors[button]; }
134 model_config_t const &GetModelConfig(uint8_t model) const { return m_config.model_config[model]; }
135 uint8_t GetPTRStartChannel() const { return m_model->ptrStartChannel; }
136 uint8_t GetPTREnableChannel() const { return m_model->ptrEnableChannel; }
138 // Setters
139 void SetRate(uint8_t rate);
140 void SetTlm(uint8_t tlm);
141 void SetPower(uint8_t power);
142 void SetDynamicPower(bool dynamicPower);
143 void SetBoostChannel(uint8_t boostChannel);
144 void SetSwitchMode(uint8_t switchMode);
145 void SetAntennaMode(uint8_t txAntenna);
146 void SetLinkMode(uint8_t linkMode);
147 void SetModelMatch(bool modelMatch);
148 void SetDefaults(bool commit);
149 void SetStorageProvider(ELRS_EEPROM *eeprom);
150 void SetVtxBand(uint8_t vtxBand);
151 void SetVtxChannel(uint8_t vtxChannel);
152 void SetVtxPower(uint8_t vtxPower);
153 void SetVtxPitmode(uint8_t vtxPitmode);
154 void SetPowerFanThreshold(uint8_t powerFanThreshold);
155 void SetFanMode(uint8_t fanMode);
156 void SetMotionMode(uint8_t motionMode);
157 void SetDvrAux(uint8_t dvrAux);
158 void SetDvrStartDelay(uint8_t dvrStartDelay);
159 void SetDvrStopDelay(uint8_t dvrStopDelay);
160 void SetButtonActions(uint8_t button, tx_button_color_t actions[2]);
161 void SetBackpackDisable(bool backpackDisable);
162 void SetBackpackTlmMode(uint8_t mode);
163 void SetPTRStartChannel(uint8_t ptrStartChannel);
164 void SetPTREnableChannel(uint8_t ptrEnableChannel);
166 // State setters
167 bool SetModelId(uint8_t modelId);
169 private:
170 #if !defined(PLATFORM_ESP32)
171 void UpgradeEepromV5ToV6();
172 void UpgradeEepromV6ToV7();
173 #endif
175 tx_config_t m_config;
176 ELRS_EEPROM *m_eeprom;
177 uint8_t m_modified;
178 model_config_t *m_model;
179 uint8_t m_modelId;
180 #if defined(PLATFORM_ESP32)
181 nvs_handle handle;
182 #endif
185 extern TxConfig config;
187 #endif
189 ///////////////////////////////////////////////////
191 #if defined(TARGET_RX)
192 constexpr uint8_t PWM_MAX_CHANNELS = 16;
194 typedef enum : uint8_t {
195 BINDSTORAGE_PERSISTENT = 0,
196 BINDSTORAGE_VOLATILE = 1,
197 BINDSTORAGE_RETURNABLE = 2,
198 } rx_config_bindstorage_t;
200 typedef union {
201 struct {
202 uint32_t failsafe:10, // us output during failsafe +988 (e.g. 512 here would be 1500us)
203 inputChannel:4, // 0-based input channel
204 inverted:1, // invert channel output
205 mode:4, // Output mode (eServoOutputMode)
206 narrow:1, // Narrow output mode (half pulse width)
207 failsafeMode:2, // failsafe output mode (eServoOutputFailsafeMode)
208 unused:10; // FUTURE: When someone complains "everyone" uses inverted polarity PWM or something :/
209 } val;
210 uint32_t raw;
211 } rx_config_pwm_t;
213 typedef struct __attribute__((packed)) {
214 uint32_t version;
215 uint8_t uid[UID_LEN];
216 uint8_t unused_padding;
217 uint8_t serial1Protocol:4, // secondary serial protocol
218 serial1Protocol_unused:4;
219 uint32_t flash_discriminator;
220 struct __attribute__((packed)) {
221 uint16_t scale; // FUTURE: Override compiled vbat scale
222 int16_t offset; // FUTURE: Override comiled vbat offset
223 } vbat;
224 uint8_t bindStorage:2, // rx_config_bindstorage_t
225 power:4,
226 antennaMode:2; // 0=0, 1=1, 2=Diversity
227 uint8_t powerOnCounter:3,
228 forceTlmOff:1,
229 rateInitialIdx:4; // Rate to start rateCycling at on boot
230 uint8_t modelId;
231 uint8_t serialProtocol:4,
232 failsafeMode:2,
233 unused:2;
234 rx_config_pwm_t pwmChannels[PWM_MAX_CHANNELS] __attribute__((aligned(4)));
235 uint8_t teamraceChannel:4,
236 teamracePosition:3,
237 teamracePitMode:1; // FUTURE: Enable pit mode when disabling model
238 uint8_t targetSysId;
239 uint8_t sourceSysId;
240 } rx_config_t;
242 class RxConfig
244 public:
245 RxConfig();
247 void Load();
248 void Commit();
250 // Getters
251 bool GetIsBound() const;
252 const uint8_t* GetUID() const { return m_config.uid; }
253 #if defined(PLATFORM_ESP8266)
254 uint8_t GetPowerOnCounter() const;
255 #else
256 uint8_t GetPowerOnCounter() const { return m_config.powerOnCounter; }
257 #endif
258 uint8_t GetModelId() const { return m_config.modelId; }
259 uint8_t GetPower() const { return m_config.power; }
260 uint8_t GetAntennaMode() const { return m_config.antennaMode; }
261 bool IsModified() const { return m_modified; }
262 #if defined(GPIO_PIN_PWM_OUTPUTS)
263 const rx_config_pwm_t *GetPwmChannel(uint8_t ch) const { return &m_config.pwmChannels[ch]; }
264 #endif
265 bool GetForceTlmOff() const { return m_config.forceTlmOff; }
266 uint8_t GetRateInitialIdx() const { return m_config.rateInitialIdx; }
267 eSerialProtocol GetSerialProtocol() const { return (eSerialProtocol)m_config.serialProtocol; }
268 #if defined(PLATFORM_ESP32)
269 eSerial1Protocol GetSerial1Protocol() const { return (eSerial1Protocol)m_config.serial1Protocol; }
270 #endif
271 uint8_t GetTeamraceChannel() const { return m_config.teamraceChannel; }
272 uint8_t GetTeamracePosition() const { return m_config.teamracePosition; }
273 eFailsafeMode GetFailsafeMode() const { return (eFailsafeMode)m_config.failsafeMode; }
274 uint8_t GetTargetSysId() const { return m_config.targetSysId; }
275 uint8_t GetSourceSysId() const { return m_config.sourceSysId; }
276 rx_config_bindstorage_t GetBindStorage() const { return (rx_config_bindstorage_t)m_config.bindStorage; }
277 bool IsOnLoan() const;
279 // Setters
280 void SetUID(uint8_t* uid);
281 void SetPowerOnCounter(uint8_t powerOnCounter);
282 void SetModelId(uint8_t modelId);
283 void SetPower(uint8_t power);
284 void SetAntennaMode(uint8_t antennaMode);
285 void SetDefaults(bool commit);
286 void SetStorageProvider(ELRS_EEPROM *eeprom);
287 #if defined(GPIO_PIN_PWM_OUTPUTS)
288 void SetPwmChannel(uint8_t ch, uint16_t failsafe, uint8_t inputCh, bool inverted, uint8_t mode, bool narrow);
289 void SetPwmChannelRaw(uint8_t ch, uint32_t raw);
290 #endif
291 void SetForceTlmOff(bool forceTlmOff);
292 void SetRateInitialIdx(uint8_t rateInitialIdx);
293 void SetSerialProtocol(eSerialProtocol serialProtocol);
294 #if defined(PLATFORM_ESP32)
295 void SetSerial1Protocol(eSerial1Protocol serial1Protocol);
296 #endif
297 void SetTeamraceChannel(uint8_t teamraceChannel);
298 void SetTeamracePosition(uint8_t teamracePosition);
299 void SetFailsafeMode(eFailsafeMode failsafeMode);
300 void SetTargetSysId(uint8_t sysID);
301 void SetSourceSysId(uint8_t sysID);
302 void SetBindStorage(rx_config_bindstorage_t value);
303 void ReturnLoan();
305 private:
306 void CheckUpdateFlashedUid(bool skipDescrimCheck);
307 void UpgradeUid(uint8_t *onLoanUid, uint8_t *boundUid);
308 void UpgradeEepromV4();
309 void UpgradeEepromV5();
310 void UpgradeEepromV6();
311 void UpgradeEepromV7V8();
313 rx_config_t m_config;
314 ELRS_EEPROM *m_eeprom;
315 bool m_modified;
318 extern RxConfig config;
320 #endif