mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_HAL_ChibiOS: return success status from serial_led_send and set_serial_led_rgb_data
This commit is contained in:
parent
bf104d7bee
commit
c7ef591a56
@ -2404,29 +2404,29 @@ void RCOutput::_set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led)
|
|||||||
setup serial LED output data for a given output channel
|
setup serial LED output data for a given output channel
|
||||||
and a LED number. LED -1 is all LEDs
|
and a LED number. LED -1 is all LEDs
|
||||||
*/
|
*/
|
||||||
void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
bool RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
||||||
{
|
{
|
||||||
if (!_initialised) {
|
if (!_initialised) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t i = 0;
|
uint8_t i = 0;
|
||||||
pwm_group *grp = find_chan(chan, i);
|
pwm_group *grp = find_chan(chan, i);
|
||||||
|
|
||||||
if (!grp) {
|
if (!grp) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (grp->serial_led_pending) {
|
if (grp->serial_led_pending) {
|
||||||
// dont allow setting new data if a send is pending
|
// dont allow setting new data if a send is pending
|
||||||
// would result in a fight over the mutex
|
// would result in a fight over the mutex
|
||||||
return;
|
return false;
|
||||||
};
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(grp->serial_led_mutex);
|
WITH_SEMAPHORE(grp->serial_led_mutex);
|
||||||
|
|
||||||
if (grp->serial_nleds == 0 || led >= grp->serial_nleds) {
|
if (grp->serial_nleds == 0 || led >= grp->serial_nleds) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((grp->current_mode != grp->led_mode) && is_led_protocol(grp->led_mode)) {
|
if ((grp->current_mode != grp->led_mode) && is_led_protocol(grp->led_mode)) {
|
||||||
@ -2443,7 +2443,7 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t
|
|||||||
}
|
}
|
||||||
grp->led_mode = MODE_PWM_NONE;
|
grp->led_mode = MODE_PWM_NONE;
|
||||||
grp->serial_nleds = 0;
|
grp->serial_nleds = 0;
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -2454,11 +2454,11 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t
|
|||||||
// Failed to set output mode
|
// Failed to set output mode
|
||||||
grp->led_mode = MODE_PWM_NONE;
|
grp->led_mode = MODE_PWM_NONE;
|
||||||
grp->serial_nleds = 0;
|
grp->serial_nleds = 0;
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
} else if (!is_led_protocol(grp->current_mode)) {
|
} else if (!is_led_protocol(grp->current_mode)) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (led == -1) {
|
if (led == -1) {
|
||||||
@ -2466,7 +2466,7 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t
|
|||||||
for (uint8_t n=0; n<grp->serial_nleds; n++) {
|
for (uint8_t n=0; n<grp->serial_nleds; n++) {
|
||||||
serial_led_set_single_rgb_data(*grp, i, n, red, green, blue);
|
serial_led_set_single_rgb_data(*grp, i, n, red, green, blue);
|
||||||
}
|
}
|
||||||
return;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if not ouput clock and trailing frames, run through all LED's to do it now
|
// if not ouput clock and trailing frames, run through all LED's to do it now
|
||||||
@ -2477,6 +2477,8 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
serial_led_set_single_rgb_data(*grp, i, uint8_t(led), red, green, blue);
|
serial_led_set_single_rgb_data(*grp, i, uint8_t(led), red, green, blue);
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -2500,26 +2502,26 @@ void RCOutput::serial_led_set_single_rgb_data(pwm_group& group, uint8_t idx, uin
|
|||||||
/*
|
/*
|
||||||
trigger send of serial led data for one group
|
trigger send of serial led data for one group
|
||||||
*/
|
*/
|
||||||
void RCOutput::serial_led_send(const uint16_t chan)
|
bool RCOutput::serial_led_send(const uint16_t chan)
|
||||||
{
|
{
|
||||||
if (!_initialised) {
|
if (!_initialised) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (led_thread_ctx == nullptr) {
|
if (led_thread_ctx == nullptr) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
pwm_group *grp = find_chan(chan, i);
|
pwm_group *grp = find_chan(chan, i);
|
||||||
if (!grp) {
|
if (!grp) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(grp->serial_led_mutex);
|
WITH_SEMAPHORE(grp->serial_led_mutex);
|
||||||
|
|
||||||
if (grp->serial_nleds == 0 || !is_led_protocol(grp->current_mode)) {
|
if (grp->serial_nleds == 0 || !is_led_protocol(grp->current_mode)) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (grp->prepared_send) {
|
if (grp->prepared_send) {
|
||||||
@ -2527,6 +2529,8 @@ void RCOutput::serial_led_send(const uint16_t chan)
|
|||||||
serial_led_pending = true;
|
serial_led_pending = true;
|
||||||
chEvtSignal(led_thread_ctx, EVT_LED_SEND);
|
chEvtSignal(led_thread_ctx, EVT_LED_SEND);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::timer_info(ExpandingString &str)
|
void RCOutput::timer_info(ExpandingString &str)
|
||||||
|
@ -246,12 +246,12 @@ public:
|
|||||||
setup serial LED output data for a given output channel
|
setup serial LED output data for a given output channel
|
||||||
and LEDs number. LED -1 is all LEDs
|
and LEDs number. LED -1 is all LEDs
|
||||||
*/
|
*/
|
||||||
void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override;
|
bool set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
trigger send of serial LED data
|
trigger send of serial LED data
|
||||||
*/
|
*/
|
||||||
void serial_led_send(const uint16_t chan) override;
|
bool serial_led_send(const uint16_t chan) override;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
rcout thread
|
rcout thread
|
||||||
|
Loading…
Reference in New Issue
Block a user