9 constexpr uint8_t LEDSEQ_RADIO_FAILED
[] = { 20, 100 }; // 200ms on, 1000ms off
10 constexpr uint8_t LEDSEQ_DISCONNECTED
[] = { 50, 50 }; // 500ms on, 500ms off
11 constexpr uint8_t LEDSEQ_WIFI_UPDATE
[] = { 2, 3 }; // 20ms on, 30ms off
12 constexpr uint8_t LEDSEQ_BINDING
[] = { 10, 10, 10, 100 }; // 2x 100ms blink, 1s pause
13 constexpr uint8_t LEDSEQ_MODEL_MISMATCH
[] = { 10, 10, 10, 10, 10, 100 }; // 3x 100ms blink, 1s pause
14 constexpr uint8_t LEDSEQ_UPDATE
[] = { 20, 5, 5, 5, 5, 40 }; // 200ms on, 2x 50ms off/on, 400ms off
16 static int8_t _pin
= -1;
17 static uint8_t _pin_inverted
;
18 static const uint8_t *_durations
;
19 static uint8_t _count
;
20 static uint8_t _counter
= 0;
21 static bool hasRGBLeds
= false;
22 static bool hasGBLeds
= false;
24 static uint16_t updateLED()
26 if (_pin
== UNDEF_PIN
)
28 return DURATION_NEVER
;
31 digitalWrite(_pin
, LOW
^ _pin_inverted
);
33 digitalWrite(_pin
, HIGH
^ _pin_inverted
);
34 if (_counter
>= _count
)
38 return _durations
[_counter
++] * 10;
41 static uint16_t flashLED(int8_t pin
, uint8_t pin_inverted
, const uint8_t durations
[], uint8_t count
)
45 _pin_inverted
= pin_inverted
;
46 _durations
= durations
;
51 static void initialize()
53 if (GPIO_PIN_LED_BLUE
!= UNDEF_PIN
)
55 pinMode(GPIO_PIN_LED_BLUE
, OUTPUT
);
56 digitalWrite(GPIO_PIN_LED_BLUE
, LOW
^ GPIO_LED_BLUE_INVERTED
);
58 if (GPIO_PIN_LED_GREEN
!= UNDEF_PIN
)
60 pinMode(GPIO_PIN_LED_GREEN
, OUTPUT
);
61 digitalWrite(GPIO_PIN_LED_GREEN
, HIGH
^ GPIO_LED_GREEN_INVERTED
);
63 if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
65 pinMode(GPIO_PIN_LED_RED
, OUTPUT
);
66 digitalWrite(GPIO_PIN_LED_RED
, LOW
^ GPIO_LED_RED_INVERTED
);
68 if (GPIO_PIN_LED_BLUE
!= UNDEF_PIN
&& GPIO_PIN_LED_GREEN
!= UNDEF_PIN
&& GPIO_PIN_LED_RED
!= UNDEF_PIN
)
71 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
);
72 digitalWrite(GPIO_PIN_LED_RED
, HIGH
);
73 digitalWrite(GPIO_PIN_LED_BLUE
, LOW
);
75 else if (GPIO_PIN_LED_BLUE
!= UNDEF_PIN
&& GPIO_PIN_LED_GREEN
!= UNDEF_PIN
&& GPIO_PIN_LED_RED
== UNDEF_PIN
)
86 #if defined(TARGET_TX)
87 static void setPowerLEDs()
91 switch (POWERMGNT::currPower())
94 digitalWrite(GPIO_PIN_LED_BLUE
, HIGH
);
95 digitalWrite(GPIO_PIN_LED_GREEN
, HIGH
);
98 digitalWrite(GPIO_PIN_LED_BLUE
, LOW
);
99 digitalWrite(GPIO_PIN_LED_GREEN
, HIGH
);
106 digitalWrite(GPIO_PIN_LED_BLUE
, HIGH
);
107 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
);
116 #if defined(TARGET_TX)
119 if (InBindingMode
&& GPIO_PIN_LED_RED
!= UNDEF_PIN
)
121 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_BINDING
, sizeof(LEDSEQ_BINDING
));
124 switch (connectionState
)
129 digitalWrite(GPIO_PIN_LED_GREEN
, HIGH
);
130 digitalWrite(GPIO_PIN_LED_RED
, LOW
);
131 digitalWrite(GPIO_PIN_LED_BLUE
, LOW
);
133 else if (GPIO_PIN_LED_GREEN
!= UNDEF_PIN
)
135 digitalWrite(GPIO_PIN_LED_GREEN
, HIGH
^ GPIO_LED_GREEN_INVERTED
);
137 if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
139 if (!connectionHasModelMatch
|| !teamraceHasModelMatch
)
141 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_MODEL_MISMATCH
, sizeof(LEDSEQ_MODEL_MISMATCH
));
143 else if (!hasRGBLeds
)
145 digitalWrite(GPIO_PIN_LED_RED
, HIGH
^ GPIO_LED_RED_INVERTED
); // turn on led
148 return DURATION_NEVER
;
152 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
);
153 digitalWrite(GPIO_PIN_LED_BLUE
, LOW
);
154 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_DISCONNECTED
, sizeof(LEDSEQ_DISCONNECTED
));
156 else if (GPIO_PIN_LED_GREEN
!= UNDEF_PIN
&& GPIO_PIN_LED_RED
!= UNDEF_PIN
)
158 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
^ GPIO_LED_GREEN_INVERTED
);
159 digitalWrite(GPIO_PIN_LED_RED
, LOW
^ GPIO_LED_RED_INVERTED
);
161 else if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
163 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_DISCONNECTED
, sizeof(LEDSEQ_DISCONNECTED
));
165 else if (GPIO_PIN_LED_GREEN
!= UNDEF_PIN
)
167 return flashLED(GPIO_PIN_LED_GREEN
, GPIO_LED_GREEN_INVERTED
, LEDSEQ_DISCONNECTED
, sizeof(LEDSEQ_DISCONNECTED
));
169 return DURATION_NEVER
;
173 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
);
174 digitalWrite(GPIO_PIN_LED_RED
, LOW
);
175 return flashLED(GPIO_PIN_LED_BLUE
, GPIO_LED_BLUE_INVERTED
, LEDSEQ_WIFI_UPDATE
, sizeof(LEDSEQ_WIFI_UPDATE
));
177 else if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
179 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_WIFI_UPDATE
, sizeof(LEDSEQ_WIFI_UPDATE
));
181 return DURATION_NEVER
;
185 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
);
186 digitalWrite(GPIO_PIN_LED_BLUE
, LOW
);
187 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_RADIO_FAILED
, sizeof(LEDSEQ_RADIO_FAILED
));
189 else if (GPIO_PIN_LED_GREEN
!= UNDEF_PIN
)
191 digitalWrite(GPIO_PIN_LED_GREEN
, LOW
^ GPIO_LED_GREEN_INVERTED
);
193 if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
195 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_RADIO_FAILED
, sizeof(LEDSEQ_RADIO_FAILED
));
197 return DURATION_NEVER
;
199 if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
201 // technically nocrossfire is {10,100} but {20,100} is close enough
202 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_RADIO_FAILED
, sizeof(LEDSEQ_RADIO_FAILED
));
205 if (GPIO_PIN_LED_RED
!= UNDEF_PIN
)
207 return flashLED(GPIO_PIN_LED_RED
, GPIO_LED_RED_INVERTED
, LEDSEQ_UPDATE
, sizeof(LEDSEQ_UPDATE
));
210 return DURATION_NEVER
;
214 device_t LED_device
= {
215 .initialize
= initialize
,