mirror of https://github.com/ArduPilot/ardupilot
AP_SerialLED: return success status from send and set_RGB
This commit is contained in:
parent
f7b67b6ef1
commit
9ed25a81fb
|
@ -53,20 +53,21 @@ bool AP_SerialLED::set_num_profiled(uint8_t chan, uint8_t num_leds)
|
|||
}
|
||||
|
||||
// set RGB value on LED number. LED number -1 is all LEDs. First LED is 0. chan is PWM output, 1..16
|
||||
void AP_SerialLED::set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
||||
bool AP_SerialLED::set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
||||
{
|
||||
if (chan >= 1 && chan <= 16) {
|
||||
hal.rcout->set_serial_led_rgb_data(chan-1, led, red, green, blue);
|
||||
return hal.rcout->set_serial_led_rgb_data(chan-1, led, red, green, blue);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// trigger sending of LED changes to LEDs
|
||||
void AP_SerialLED::send(uint8_t chan)
|
||||
bool AP_SerialLED::send(uint8_t chan)
|
||||
{
|
||||
if (chan >= 1 && chan <= 16) {
|
||||
hal.rcout->serial_led_send(chan-1);
|
||||
return hal.rcout->serial_led_send(chan-1);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // AP_SERIALLED_ENABLED
|
||||
|
|
|
@ -39,10 +39,10 @@ public:
|
|||
void set_RGB_mask(uint8_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue);
|
||||
|
||||
// set RGB value on LED. LED -1 is all LEDs. LED 0 is first LED. chan is PWM output, 1..16
|
||||
void set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue);
|
||||
bool set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue);
|
||||
|
||||
// trigger sending of LED changes to LEDs
|
||||
void send(uint8_t chan);
|
||||
bool send(uint8_t chan);
|
||||
|
||||
// singleton support
|
||||
static AP_SerialLED *get_singleton(void) {
|
||||
|
|
Loading…
Reference in New Issue