HAL_SITL: allow more than 32 LEDs on a pin

This commit is contained in:
Andrew Tridgell 2020-02-09 21:35:07 +11:00
parent 669b98c6df
commit 09d10df3a3
2 changed files with 15 additions and 10 deletions

View File

@ -89,7 +89,7 @@ void RCOutput::push(void)
*/
bool RCOutput::set_neopixel_num_LEDs(const uint16_t chan, uint8_t num_leds)
{
if (chan > 15 || num_leds > 32) {
if (chan > 15 || num_leds > 64) {
return false;
}
SITL::SITL *sitl = AP::sitl();
@ -100,20 +100,25 @@ bool RCOutput::set_neopixel_num_LEDs(const uint16_t chan, uint8_t num_leds)
return false;
}
void RCOutput::set_neopixel_rgb_data(const uint16_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue)
void RCOutput::set_neopixel_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue)
{
if (chan > 15) {
return;
}
SITL::SITL *sitl = AP::sitl();
if (sitl) {
for (uint8_t i=0; i<32; i++) {
if ((1U<<i) & ledmask) {
sitl->led.rgb[chan][i].rgb[0] = red;
sitl->led.rgb[chan][i].rgb[1] = green;
sitl->led.rgb[chan][i].rgb[2] = blue;
}
if (led == -1) {
for (uint8_t i=0; i < sitl->led.num_leds[chan]; i++) {
set_neopixel_rgb_data(chan, i, red, green, blue);
}
return;
}
if (led < -1 || led >= sitl->led.num_leds[chan]) {
return;
}
if (sitl) {
sitl->led.rgb[chan][led].rgb[0] = red;
sitl->led.rgb[chan][led].rgb[1] = green;
sitl->led.rgb[chan][led].rgb[2] = blue;
}
}

View File

@ -31,7 +31,7 @@ public:
Serial LED emulation
*/
bool set_neopixel_num_LEDs(const uint16_t chan, uint8_t num_leds) override;
void set_neopixel_rgb_data(const uint16_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue) override;
void set_neopixel_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override;
void neopixel_send(void) override;
private: