mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HAL_PX4: fixed RC failsafe for SBUS on FMUv4
the FMUv4 SBUS parser sets timestamp_last_signal even if we are in failsafe thanks to Mark Whitehorn for finding this
This commit is contained in:
parent
551fa67673
commit
fc4caf51e9
@ -26,7 +26,15 @@ void PX4RCInput::init()
|
|||||||
bool PX4RCInput::new_input()
|
bool PX4RCInput::new_input()
|
||||||
{
|
{
|
||||||
pthread_mutex_lock(&rcin_mutex);
|
pthread_mutex_lock(&rcin_mutex);
|
||||||
bool valid = _rcin.timestamp_last_signal != _last_read || _override_valid;
|
bool valid = _rcin.timestamp_last_signal != _last_read;
|
||||||
|
if (_rcin.rc_failsafe) {
|
||||||
|
// don't consider input valid if we are in RC failsafe.
|
||||||
|
valid = false;
|
||||||
|
}
|
||||||
|
if (_override_valid) {
|
||||||
|
// if we have RC overrides active, then always consider it valid
|
||||||
|
valid = true;
|
||||||
|
}
|
||||||
_last_read = _rcin.timestamp_last_signal;
|
_last_read = _rcin.timestamp_last_signal;
|
||||||
_override_valid = false;
|
_override_valid = false;
|
||||||
pthread_mutex_unlock(&rcin_mutex);
|
pthread_mutex_unlock(&rcin_mutex);
|
||||||
|
Loading…
Reference in New Issue
Block a user