From e09e9a313ecb5e78046093c537421948230b0911 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 27 Jan 2016 19:25:40 -0800 Subject: [PATCH] Copter: interpret MAV_FRAME_GLOBAL_RELATIVE_ALT as MAV_FRAME_GLOBAL_RELATIVE_ALT_INT --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 309752873c..293b05362e 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1727,6 +1727,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // check for supported coordinate frames if (packet.coordinate_frame != MAV_FRAME_GLOBAL_INT && + packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT && // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT && packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) { break; @@ -1751,6 +1752,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) loc.lng = packet.lon_int; loc.alt = packet.alt*100; switch (packet.coordinate_frame) { + case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: loc.flags.relative_alt = true; loc.flags.terrain_alt = false;