mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: add nullptr check for mavlink channel 0
This commit is contained in:
parent
b860676f12
commit
cfe4ec4d1f
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user