From 330b52194f6631654115bd5943c2b83bb9220157 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 19 Nov 2014 12:06:30 -0800 Subject: [PATCH] Copter: change to switch order in guided spline No functional change --- ArduCopter/GCS_Mavlink.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 82a3580d8f..cd1d78b555 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1381,12 +1381,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) loc.lng = packet.lon_int; loc.alt = packet.alt*100; switch (packet.coordinate_frame) { - default: - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_INT: - loc.flags.relative_alt = false; - loc.flags.terrain_alt = false; - break; case MAV_FRAME_GLOBAL_RELATIVE_ALT: case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: loc.flags.relative_alt = true; @@ -1397,6 +1391,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) loc.flags.relative_alt = true; loc.flags.terrain_alt = true; break; + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_INT: + default: + loc.flags.relative_alt = false; + loc.flags.terrain_alt = false; + break; } pos_ned = pv_location_to_vector(loc); }