diff --git a/libraries/AP_HAL_ChibiOS/RCInput.cpp b/libraries/AP_HAL_ChibiOS/RCInput.cpp index 1351ac92bb..9450a4acc4 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCInput.cpp @@ -73,13 +73,12 @@ bool RCInput::new_input() if (!_init) { return false; } - if (!rcin_mutex.take_nonblocking()) { - return false; + bool valid; + { + WITH_SEMAPHORE(rcin_mutex); + valid = _rcin_timestamp_last_signal != _last_read; + _last_read = _rcin_timestamp_last_signal; } - bool valid = _rcin_timestamp_last_signal != _last_read; - - _last_read = _rcin_timestamp_last_signal; - rcin_mutex.give(); #if HAL_RCINPUT_WITH_AP_RADIO if (!_radio_init) { diff --git a/libraries/AP_HAL_ChibiOS/RCInput.h b/libraries/AP_HAL_ChibiOS/RCInput.h index 1751ea842d..7f3de7d419 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.h +++ b/libraries/AP_HAL_ChibiOS/RCInput.h @@ -63,7 +63,7 @@ private: uint64_t _last_read; uint8_t _num_channels; - Semaphore rcin_mutex; + HAL_Semaphore_Recursive rcin_mutex; int16_t _rssi = -1; uint32_t _rcin_timestamp_last_signal; bool _init;