Browse Source

ArduPlane: add and use accessor for last-RADIO_STATUS.remrssi-ms

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
f59d2fdbf4
  1. 4
      ArduPlane/system.cpp

4
ArduPlane/system.cpp

@ -324,8 +324,8 @@ void Plane::check_long_failsafe() @@ -324,8 +324,8 @@ void Plane::check_long_failsafe()
failsafe_long_on_event(FAILSAFE_GCS, ModeReason::GCS_FAILSAFE);
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
gcs().chan(0) != nullptr &&
gcs().chan(0)->last_radio_status_remrssi_ms != 0 &&
(tnow - gcs().chan(0)->last_radio_status_remrssi_ms) > g.fs_timeout_long*1000) {
gcs().chan(0)->last_radio_status_remrssi_ms() != 0 &&
(tnow - gcs().chan(0)->last_radio_status_remrssi_ms()) > g.fs_timeout_long*1000) {
failsafe_long_on_event(FAILSAFE_GCS, ModeReason::GCS_FAILSAFE);
}
} else {

Loading…
Cancel
Save