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
This commit is contained in:
Randy Mackay 2014-09-09 22:19:20 +09:00
parent bf18fb896a
commit 294f836c8c

View File

@ -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;