HAL_ChibiOS: switch between IOMCU and RCProt rapidly

keep the RCProtocol decoder going when IOMCU being used, allowing for fast failover
between IOMCU RC input and uart RC input
This commit is contained in:
Andrew Tridgell 2022-03-27 17:30:19 +11:00 committed by Randy Mackay
parent fb644b2078
commit e079d93b2d
1 changed files with 1 additions and 1 deletions

View File

@ -181,7 +181,7 @@ void RCInput::_timer_tick(void)
_rcin_last_iomcu_ms = 0; _rcin_last_iomcu_ms = 0;
} }
if (!have_iocmu_rc && rcprot.new_input()) { if (rcprot.new_input() && !have_iocmu_rc) {
WITH_SEMAPHORE(rcin_mutex); WITH_SEMAPHORE(rcin_mutex);
_rcin_timestamp_last_signal = AP_HAL::micros(); _rcin_timestamp_last_signal = AP_HAL::micros();
_num_channels = rcprot.num_channels(); _num_channels = rcprot.num_channels();