mirror of https://github.com/ArduPilot/ardupilot
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:
parent
4e414c02f5
commit
dcd7799ec9
|
@ -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) {
|
||||
mode = MODE_PWM_NONE;
|
||||
}
|
||||
if (mode > MODE_PWM_NORMAL) {
|
||||
fast_channel_mask |= group.ch_mask;
|
||||
}
|
||||
if (group.current_mode != mode) {
|
||||
group.current_mode = mode;
|
||||
set_group_mode(group);
|
||||
|
|
Loading…
Reference in New Issue