AP_HAL_ChibiOS: allow further LED channels to be allocated at the same length

This commit is contained in:
Andy Piper 2021-03-13 14:18:37 +00:00 committed by Andrew Tridgell
parent a6800b8c47
commit 968d05a637

View File

@ -1927,11 +1927,16 @@ bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, ou
// we must hold the LED mutex while resizing the array // we must hold the LED mutex while resizing the array
WITH_SEMAPHORE(grp->serial_led_mutex); WITH_SEMAPHORE(grp->serial_led_mutex);
// if already allocated then return // if already allocated a different size then return
if (grp->serial_nleds > 0 || num_leds == 0 if ((grp->serial_nleds > 0 && num_leds != grp->serial_nleds)
|| (mode != MODE_NEOPIXEL && mode != MODE_PROFILED)) { || (mode != MODE_NEOPIXEL && mode != MODE_PROFILED)) {
return false; return false;
} }
// if already allocated this channel
if (grp->serial_nleds > 0 && num_leds == grp->serial_nleds
&& grp->serial_led_data[i] != nullptr) {
return false;
}
switch (mode) { switch (mode) {
case MODE_NEOPIXEL: { case MODE_NEOPIXEL: {