diff --git a/ArduPlane/GCS_Plane.cpp b/ArduPlane/GCS_Plane.cpp index 3413401dde..39989dba93 100644 --- a/ArduPlane/GCS_Plane.cpp +++ b/ArduPlane/GCS_Plane.cpp @@ -98,13 +98,6 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void) control_sensors_health |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; } - control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; - control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; - uint32_t last_valid = plane.failsafe.last_valid_rc_ms; - if (millis() - last_valid < 200) { - control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; - } - #if AP_TERRAIN_AVAILABLE switch (plane.terrain.status()) { case AP_Terrain::TerrainStatusDisabled: