diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 57d69412ae..a9e8eb79ff 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -81,12 +81,20 @@ void ChibiRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) grp_ch_mask |= (1U<printf("RCOutput: Failed to set PWM frequency req %x set %x\n", (unsigned)chmask, (unsigned)update_mask); } @@ -195,7 +203,10 @@ void ChibiRCOutput::push_local(void) uint8_t chan = pwm_group_list[i].chan[j]; if (outmask & (1UL<= _esc_pwm_max) { diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 06a1900ab6..ef19dcf4b2 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -79,6 +79,8 @@ private: uint16_t period[16]; uint8_t num_channels; bool corked; + // mask of channels that are running in high speed + uint16_t fast_channel_mask; // push out values to local PWM void push_local(void);