Plane: add nullptr check for mavlink channel 0

This commit is contained in:
Peter Barker 2019-08-06 12:33:36 +10:00 committed by Peter Barker
parent b860676f12
commit cfe4ec4d1f

View File

@ -342,6 +342,7 @@ void Plane::check_long_failsafe()
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_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) {
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);