mirror of https://github.com/ArduPilot/ardupilot
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:
parent
9ba73d362d
commit
0ae1ac182a
|
@ -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();
|
||||||
|
|
Loading…
Reference in New Issue