Silence unused-variable warning (#2872)
[ExpressLRS.git] / src / lib / LED / devLED.cpp
blobe9dbfb73d8496f4628715ba5c925aacff5e09e60
1 #include "targets.h"
2 #include "common.h"
3 #include "devLED.h"
5 #include "crsf_protocol.h"
6 #include "POWERMGNT.h"
8 #ifdef HAS_LED
10 /* Set red led to default */
11 #ifndef GPIO_PIN_LED_RED
12 #ifdef GPIO_PIN_LED
13 #define GPIO_PIN_LED_RED GPIO_PIN_LED
14 #else
15 #define GPIO_PIN_LED_RED UNDEF_PIN
16 #endif
17 #endif
18 #ifndef GPIO_PIN_LED
19 #define GPIO_PIN_LED GPIO_PIN_LED_RED
20 #endif
21 #ifndef GPIO_PIN_LED_GREEN
22 #define GPIO_PIN_LED_GREEN UNDEF_PIN
23 #endif
24 #ifndef GPIO_PIN_LED_BLUE
25 #define GPIO_PIN_LED_BLUE UNDEF_PIN
26 #endif
27 #ifndef GPIO_LED_RED_INVERTED
28 #define GPIO_LED_RED_INVERTED 0
29 #endif
30 #ifndef GPIO_LED_GREEN_INVERTED
31 #define GPIO_LED_GREEN_INVERTED 0
32 #endif
33 #ifndef GPIO_LED_BLUE_INVERTED
34 #define GPIO_LED_BLUE_INVERTED 0
35 #endif
37 #if defined(TARGET_RX)
38 extern bool connectionHasModelMatch;
39 #endif
41 constexpr uint8_t LEDSEQ_RADIO_FAILED[] = { 20, 100 }; // 200ms on, 1000ms off
42 constexpr uint8_t LEDSEQ_DISCONNECTED[] = { 50, 50 }; // 500ms on, 500ms off
43 constexpr uint8_t LEDSEQ_WIFI_UPDATE[] = { 2, 3 }; // 20ms on, 30ms off
44 constexpr uint8_t LEDSEQ_BINDING[] = { 10, 10, 10, 100 }; // 2x 100ms blink, 1s pause
45 constexpr uint8_t LEDSEQ_MODEL_MISMATCH[] = { 10, 10, 10, 10, 10, 100 }; // 3x 100ms blink, 1s pause
46 constexpr uint8_t LEDSEQ_UPDATE[] = { 20, 5, 5, 5, 5, 40 }; // 200ms on, 2x 50ms off/on, 400ms off
48 static uint8_t _pin = -1;
49 static uint8_t _pin_inverted;
50 static const uint8_t *_durations;
51 static uint8_t _count;
52 static uint8_t _counter = 0;
53 static bool hasRGBLeds = false;
54 #if defined(TARGET_TX)
55 static bool hasGBLeds = false;
56 #endif
58 static uint16_t updateLED()
60 if (_pin == UNDEF_PIN)
62 return DURATION_NEVER;
64 if(_counter % 2 == 1)
65 digitalWrite(_pin, LOW ^ _pin_inverted);
66 else
67 digitalWrite(_pin, HIGH ^ _pin_inverted);
68 if (_counter >= _count)
70 _counter = 0;
72 return _durations[_counter++] * 10;
75 static uint16_t flashLED(uint8_t pin, uint8_t pin_inverted, const uint8_t durations[], uint8_t count)
77 _counter = 0;
78 _pin = pin;
79 _pin_inverted = pin_inverted;
80 _durations = durations;
81 _count = count;
82 return updateLED();
85 static void initialize()
87 // TODO for future PR, remove TARGET_TX, TARGET_RX, and TARGET_TX_FM30 defines.
88 #if defined(TARGET_TX)
89 if (GPIO_PIN_LED_BLUE != UNDEF_PIN)
91 pinMode(GPIO_PIN_LED_BLUE, OUTPUT);
92 digitalWrite(GPIO_PIN_LED_BLUE, LOW ^ GPIO_LED_BLUE_INVERTED);
94 if (GPIO_PIN_LED_GREEN != UNDEF_PIN)
96 pinMode(GPIO_PIN_LED_GREEN, OUTPUT);
97 digitalWrite(GPIO_PIN_LED_GREEN, HIGH ^ GPIO_LED_GREEN_INVERTED);
99 if (GPIO_PIN_LED_RED != UNDEF_PIN)
101 pinMode(GPIO_PIN_LED_RED, OUTPUT);
102 digitalWrite(GPIO_PIN_LED_RED, LOW ^ GPIO_LED_RED_INVERTED);
104 if (GPIO_PIN_LED_BLUE != UNDEF_PIN && GPIO_PIN_LED_GREEN != UNDEF_PIN && GPIO_PIN_LED_RED != UNDEF_PIN)
106 hasRGBLeds = true;
107 digitalWrite(GPIO_PIN_LED_GREEN, LOW);
108 digitalWrite(GPIO_PIN_LED_RED, HIGH);
109 digitalWrite(GPIO_PIN_LED_BLUE, LOW);
111 else if (GPIO_PIN_LED_BLUE != UNDEF_PIN && GPIO_PIN_LED_GREEN != UNDEF_PIN && GPIO_PIN_LED_RED == UNDEF_PIN)
113 hasGBLeds = true;
115 #if defined(TARGET_TX_FM30)
116 pinMode(GPIO_PIN_LED_RED_GREEN, OUTPUT); // Green LED on "Red" LED (off)
117 digitalWrite(GPIO_PIN_LED_RED_GREEN, HIGH);
118 pinMode(GPIO_PIN_LED_GREEN_RED, OUTPUT); // Red LED on "Green" LED (off)
119 digitalWrite(GPIO_PIN_LED_GREEN_RED, HIGH);
120 #endif
121 #endif
122 #if defined(TARGET_RX)
123 if (GPIO_PIN_LED_GREEN != UNDEF_PIN)
125 pinMode(GPIO_PIN_LED_GREEN, OUTPUT);
126 digitalWrite(GPIO_PIN_LED_GREEN, LOW ^ GPIO_LED_GREEN_INVERTED);
128 if (GPIO_PIN_LED_RED != UNDEF_PIN)
130 pinMode(GPIO_PIN_LED_RED, OUTPUT);
131 digitalWrite(GPIO_PIN_LED_RED, LOW ^ GPIO_LED_RED_INVERTED);
133 if (GPIO_PIN_LED != UNDEF_PIN)
135 pinMode(GPIO_PIN_LED, OUTPUT);
136 digitalWrite(GPIO_PIN_LED, LOW ^ GPIO_LED_RED_INVERTED);
138 #endif
141 static int timeout()
143 return updateLED();
146 #if !defined(TARGET_RX)
147 static void setPowerLEDs()
149 if (hasGBLeds)
151 switch (POWERMGNT::currPower())
153 case PWR_250mW:
154 digitalWrite(GPIO_PIN_LED_BLUE, HIGH);
155 digitalWrite(GPIO_PIN_LED_GREEN, HIGH);
156 break;
157 case PWR_500mW:
158 digitalWrite(GPIO_PIN_LED_BLUE, LOW);
159 digitalWrite(GPIO_PIN_LED_GREEN, HIGH);
160 break;
161 case PWR_10mW:
162 case PWR_25mW:
163 case PWR_50mW:
164 case PWR_100mW:
165 default:
166 digitalWrite(GPIO_PIN_LED_BLUE, HIGH);
167 digitalWrite(GPIO_PIN_LED_GREEN, LOW);
168 break;
172 #endif
174 static int event()
176 #if defined(TARGET_RX)
177 if (InBindingMode && GPIO_PIN_LED != UNDEF_PIN)
179 return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_BINDING, sizeof(LEDSEQ_BINDING));
181 #else
182 setPowerLEDs();
183 #endif
184 switch (connectionState)
186 case connected:
187 #if defined(TARGET_TX)
188 if (hasRGBLeds)
190 digitalWrite(GPIO_PIN_LED_GREEN, HIGH);
191 digitalWrite(GPIO_PIN_LED_RED, LOW);
192 digitalWrite(GPIO_PIN_LED_BLUE, LOW);
194 else if (GPIO_PIN_LED_RED != UNDEF_PIN)
196 digitalWrite(GPIO_PIN_LED_RED, HIGH ^ GPIO_LED_RED_INVERTED);
198 #endif
199 #if defined(TARGET_RX)
200 if (GPIO_PIN_LED_GREEN != UNDEF_PIN)
202 digitalWrite(GPIO_PIN_LED_GREEN, HIGH ^ GPIO_LED_GREEN_INVERTED);
205 if (GPIO_PIN_LED_RED != UNDEF_PIN)
207 digitalWrite(GPIO_PIN_LED_RED, HIGH ^ GPIO_LED_RED_INVERTED);
210 if (GPIO_PIN_LED != UNDEF_PIN)
212 if (!connectionHasModelMatch || !teamraceHasModelMatch)
214 return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_MODEL_MISMATCH, sizeof(LEDSEQ_MODEL_MISMATCH));
216 else
218 digitalWrite(GPIO_PIN_LED, HIGH ^ GPIO_LED_RED_INVERTED); // turn on led
221 #endif
222 return DURATION_NEVER;
223 case disconnected:
224 #if defined(TARGET_TX)
225 if (hasRGBLeds)
227 digitalWrite(GPIO_PIN_LED_GREEN, LOW);
228 digitalWrite(GPIO_PIN_LED_BLUE, LOW);
229 return flashLED(GPIO_PIN_LED_RED, GPIO_LED_RED_INVERTED, LEDSEQ_DISCONNECTED, sizeof(LEDSEQ_DISCONNECTED));
231 else if (GPIO_PIN_LED_RED != UNDEF_PIN)
233 digitalWrite(GPIO_PIN_LED_RED, LOW ^ GPIO_LED_RED_INVERTED);
235 #endif
236 #if defined(TARGET_RX)
237 if (GPIO_PIN_LED_GREEN != UNDEF_PIN)
239 digitalWrite(GPIO_PIN_LED_GREEN, LOW ^ GPIO_LED_GREEN_INVERTED);
241 if (GPIO_PIN_LED_RED != UNDEF_PIN)
243 digitalWrite(GPIO_PIN_LED_RED, LOW ^ GPIO_LED_RED_INVERTED);
245 if (GPIO_PIN_LED != UNDEF_PIN)
247 return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_DISCONNECTED, sizeof(LEDSEQ_DISCONNECTED));
249 else if (GPIO_PIN_LED_GREEN != UNDEF_PIN)
251 return flashLED(GPIO_PIN_LED_GREEN, GPIO_LED_GREEN_INVERTED, LEDSEQ_DISCONNECTED, sizeof(LEDSEQ_DISCONNECTED));
253 #endif
254 return DURATION_NEVER;
255 case wifiUpdate:
256 #if defined(TARGET_TX)
257 if (hasRGBLeds)
259 digitalWrite(GPIO_PIN_LED_GREEN, LOW);
260 digitalWrite(GPIO_PIN_LED_RED, LOW);
261 return flashLED(GPIO_PIN_LED_BLUE, GPIO_LED_BLUE_INVERTED, LEDSEQ_WIFI_UPDATE, sizeof(LEDSEQ_WIFI_UPDATE));
263 else if (GPIO_PIN_LED_RED != UNDEF_PIN)
265 return flashLED(GPIO_PIN_LED_RED, GPIO_LED_RED_INVERTED, LEDSEQ_WIFI_UPDATE, sizeof(LEDSEQ_WIFI_UPDATE));
267 return DURATION_NEVER;
268 #endif
269 #if defined(TARGET_RX)
270 if (GPIO_PIN_LED != UNDEF_PIN)
272 return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_WIFI_UPDATE, sizeof(LEDSEQ_WIFI_UPDATE));
274 #else
275 return DURATION_NEVER;
276 #endif
277 case radioFailed:
278 if (hasRGBLeds)
280 digitalWrite(GPIO_PIN_LED_GREEN, LOW);
281 digitalWrite(GPIO_PIN_LED_BLUE, LOW);
282 return flashLED(GPIO_PIN_LED_RED, GPIO_LED_RED_INVERTED, LEDSEQ_RADIO_FAILED, sizeof(LEDSEQ_RADIO_FAILED));
284 else if (GPIO_PIN_LED_GREEN != UNDEF_PIN)
286 digitalWrite(GPIO_PIN_LED_GREEN, LOW ^ GPIO_LED_GREEN_INVERTED);
288 if (GPIO_PIN_LED_RED != UNDEF_PIN)
290 return flashLED(GPIO_PIN_LED_RED, GPIO_LED_RED_INVERTED, LEDSEQ_RADIO_FAILED, sizeof(LEDSEQ_RADIO_FAILED));
292 else if (GPIO_PIN_LED != UNDEF_PIN)
294 return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_RADIO_FAILED, sizeof(LEDSEQ_RADIO_FAILED));
296 return DURATION_NEVER;
297 case noCrossfire:
298 if (GPIO_PIN_LED_RED != UNDEF_PIN)
300 // technically nocrossfire is {10,100} but {20,100} is close enough
301 return flashLED(GPIO_PIN_LED_RED, GPIO_LED_RED_INVERTED, LEDSEQ_RADIO_FAILED, sizeof(LEDSEQ_RADIO_FAILED));
303 else if (GPIO_PIN_LED != UNDEF_PIN)
305 return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_RADIO_FAILED, sizeof(LEDSEQ_RADIO_FAILED));
307 case serialUpdate:
308 if (GPIO_PIN_LED_RED != UNDEF_PIN)
310 return flashLED(GPIO_PIN_LED_RED, GPIO_LED_RED_INVERTED, LEDSEQ_UPDATE, sizeof(LEDSEQ_UPDATE));
312 default:
313 return DURATION_NEVER;
317 device_t LED_device = {
318 .initialize = initialize,
319 .start = event,
320 .event = event,
321 .timeout = timeout
324 #endif