mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_ChibiOS: use recursive mutex for RCInput
This commit is contained in:
parent
50a6d63101
commit
b5435d6a24
@ -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) {
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user