HAL_ChibiOS: fixed DShot output on fixed wing

we need to mark the channels as 'fast' for DShot to enable properly
This commit is contained in:
Andrew Tridgell 2018-05-21 10:20:46 +10:00
parent 4e414c02f5
commit dcd7799ec9
1 changed files with 3 additions and 0 deletions

View File

@ -647,6 +647,9 @@ void RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
if (mode_requires_dma(mode) && !group.have_up_dma) { if (mode_requires_dma(mode) && !group.have_up_dma) {
mode = MODE_PWM_NONE; mode = MODE_PWM_NONE;
} }
if (mode > MODE_PWM_NORMAL) {
fast_channel_mask |= group.ch_mask;
}
if (group.current_mode != mode) { if (group.current_mode != mode) {
group.current_mode = mode; group.current_mode = mode;
set_group_mode(group); set_group_mode(group);