AP_SerialLED: check for valid channel
This commit is contained in:
parent
bc7651cfcb
commit
8ad2920151
@ -30,7 +30,10 @@ 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
|
||||||
|
Loading…
Reference in New Issue
Block a user