From cac10a3041b2c0bbf6e221c94444b8f3f97f4fdd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 9 Sep 2014 22:19:20 +0900 Subject: [PATCH] Copter: never send unhealthy terrain status Copter does not yet rely on the terrain data (it's for informational purposes only) so we will temporarily disable the failure flags to the GCS to avoid support calls --- ArduCopter/GCS_Mavlink.pde | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index ec3b5c5d5c..9c6f3d3046 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -224,9 +224,10 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) case AP_Terrain::TerrainStatusDisabled: break; case AP_Terrain::TerrainStatusUnhealthy: - control_sensors_present |= MAV_SYS_STATUS_TERRAIN; - control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN; - break; + // To-Do: restore unhealthy terrain status reporting once terrain is used in copter + //control_sensors_present |= MAV_SYS_STATUS_TERRAIN; + //control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN; + //break; case AP_Terrain::TerrainStatusOK: control_sensors_present |= MAV_SYS_STATUS_TERRAIN; control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;