Browse Source

AP_SerialLED: check for valid channel

master
Andrew Tridgell 5 years ago committed by Randy Mackay
parent
commit
1858ebcefc
  1. 3
      libraries/AP_SerialLED/AP_SerialLED.cpp

3
libraries/AP_SerialLED/AP_SerialLED.cpp

@ -30,8 +30,11 @@ AP_SerialLED::AP_SerialLED() @@ -30,8 +30,11 @@ AP_SerialLED::AP_SerialLED()
// set number of LEDs per pin
bool AP_SerialLED::set_num_LEDs(uint8_t chan, uint8_t num_leds)
{
if (chan >= 1 && chan <= 16 && num_leds <= 32) {
return hal.rcout->set_neopixel_num_LEDs(chan-1, num_leds);
}
return false;
}
// set RGB value on mask of LEDs. chan is PWM output, 1..16
void AP_SerialLED::set_RGB(uint8_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue)

Loading…
Cancel
Save