AP_SerialLED: check for valid channel

This commit is contained in:
Andrew Tridgell 2019-11-04 13:03:57 +11:00 committed by Randy Mackay
parent 6cfb230e14
commit 1858ebcefc
1 changed files with 4 additions and 1 deletions

View File

@ -30,8 +30,11 @@ AP_SerialLED::AP_SerialLED()
// set number of LEDs per pin // set number of LEDs per pin
bool AP_SerialLED::set_num_LEDs(uint8_t chan, uint8_t num_leds) 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 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 // 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) void AP_SerialLED::set_RGB(uint8_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue)