mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
HAL_ChibiOS: use separate parameter for detect timeout
This commit is contained in:
parent
613d7a47ba
commit
7db19cfae0
@ -38,7 +38,7 @@ void RCInput::init()
|
||||
chMtxObjectInit(&rcin_mutex);
|
||||
_init = true;
|
||||
//timeout starts from the initialisation
|
||||
_rcin_timestamp_last_signal = AP_HAL::micros();
|
||||
_rcin_detect_timeout = AP_HAL::micros();
|
||||
}
|
||||
|
||||
bool RCInput::new_input()
|
||||
@ -187,8 +187,8 @@ void RCInput::_timer_tick(void)
|
||||
chMtxUnlock(&rcin_mutex);
|
||||
}
|
||||
//we reset if nothing detected for SIG_DETECT_TIMEOUT_US
|
||||
if (AP_HAL::micros() - _rcin_timestamp_last_signal > SIG_DETECT_TIMEOUT_US) {
|
||||
_rcin_timestamp_last_signal = AP_HAL::micros();
|
||||
if (AP_HAL::micros() - _rcin_detect_timeout > SIG_DETECT_TIMEOUT_US) {
|
||||
_rcin_detect_timeout = AP_HAL::micros();
|
||||
sig_reader.invert();
|
||||
}
|
||||
#endif
|
||||
|
@ -62,6 +62,7 @@ private:
|
||||
mutex_t rcin_mutex;
|
||||
int16_t _rssi = -1;
|
||||
uint32_t _rcin_timestamp_last_signal;
|
||||
uint32_t _rcin_detect_timeout;
|
||||
bool _init;
|
||||
#ifdef HAL_RCINPUT_WITH_AP_RADIO
|
||||
bool _radio_init;
|
||||
|
Loading…
Reference in New Issue
Block a user