From aa5e74a5d9df11d21b4daef59448e4b856af4cd7 Mon Sep 17 00:00:00 2001 From: WillyZehnder Date: Sat, 19 Jun 2021 10:58:18 +0200 Subject: [PATCH] Plane: GCS_Plane.cpp Fix chronological sequence to avoid inappropriate critical warning CRT:NoRCReceiver by ensuring the call of plane.failsafe.last_valid_rc_ms before calling millis() --- ArduPlane/GCS_Plane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Plane.cpp b/ArduPlane/GCS_Plane.cpp index e85be23603..deca2aa804 100644 --- a/ArduPlane/GCS_Plane.cpp +++ b/ArduPlane/GCS_Plane.cpp @@ -114,7 +114,8 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void) control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; - if (millis() - plane.failsafe.last_valid_rc_ms < 200) { + uint32_t last_valid = plane.failsafe.last_valid_rc_ms; + if (millis() - last_valid < 200) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; }