mirror of https://github.com/ArduPilot/ardupilot
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:
parent
b5d75b287d
commit
aa5e74a5d9
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue