Browse Source

AP_IOMCU: fixed handling of RC ignore failsafe option

this allows for ignoring SBUS failsafe on boards using an IOMCU
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
fdff355a8a
  1. 3
      libraries/AP_IOMCU/AP_IOMCU.cpp

3
libraries/AP_IOMCU/AP_IOMCU.cpp

@ -291,6 +291,9 @@ void AP_IOMCU::read_rc_input() @@ -291,6 +291,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…
Cancel
Save