From db89bd6f039616b9cd15fd26f071d35d04ae3f43 Mon Sep 17 00:00:00 2001
From: Arthur Benemann <arthur.benemann@gmail.com>
Date: Tue, 18 Nov 2014 12:08:06 -0800
Subject: [PATCH] Copter: correct frame/location of guided spline

---
 ArduCopter/GCS_Mavlink.pde | 6 +++++-
 1 file changed, 5 insertions(+), 1 deletion(-)

diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index f138ba03e..82a3580d8 100644
--- a/ArduCopter/GCS_Mavlink.pde
+++ b/ArduCopter/GCS_Mavlink.pde
@@ -1379,16 +1379,20 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
             Location loc;
             loc.lat = packet.lat_int;
             loc.lng = packet.lon_int;
-            loc.alt = packet.alt;
+            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;
                     loc.flags.terrain_alt = false;
                     break;
+                case MAV_FRAME_GLOBAL_TERRAIN_ALT:
                 case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
                     loc.flags.relative_alt = true;
                     loc.flags.terrain_alt = true;
-- 
GitLab