AP_HAL_ChibiOS: output initializing from PWM banner when not available

This commit is contained in:
Andy Piper 2021-08-09 21:36:09 +01:00 committed by Randy Mackay
parent b9598dac00
commit 68fd87091c
1 changed files with 5 additions and 0 deletions

View File

@ -964,6 +964,11 @@ void RCOutput::set_output_mode(uint16_t mask, const enum output_mode mode)
*/
bool RCOutput::get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) const
{
if (!hal.scheduler->is_system_initialized()) {
hal.util->snprintf(banner_msg, banner_msg_len, "RCOut: Initialising");
return true;
}
// create array of each channel's mode
output_mode ch_mode[chan_offset + NUM_GROUPS * ARRAY_SIZE(pwm_group::chan)] = {};
bool have_nonzero_modes = false;