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()
This commit is contained in:
WillyZehnder 2021-06-19 10:58:18 +02:00 committed by Andrew Tridgell
parent 5f3f5e9d75
commit 8f0d04ad68

View File

@ -114,7 +114,8 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
control_sensors_enabled |= 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; control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
} }