mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_IOMCU: fixed handling of RC ignore failsafe option
this allows for ignoring SBUS failsafe on boards using an IOMCU
This commit is contained in:
parent
b633e62b89
commit
d4d1287261
@ -288,6 +288,9 @@ void AP_IOMCU::read_rc_input()
|
||||
if (!read_registers(PAGE_RAW_RCIN, 0, sizeof(rc_input)/2, r)) {
|
||||
return;
|
||||
}
|
||||
if (rc_input.flags_failsafe && rc().ignore_rc_failsafe()) {
|
||||
rc_input.flags_failsafe = false;
|
||||
}
|
||||
if (rc_input.flags_rc_ok && !rc_input.flags_failsafe) {
|
||||
rc_last_input_ms = AP_HAL::millis();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user