Copter: interpret MAV_FRAME_GLOBAL_RELATIVE_ALT as MAV_FRAME_GLOBAL_RELATIVE_ALT_INT

This commit is contained in:
Jonathan Challinger 2016-01-27 19:25:40 -08:00 committed by Randy Mackay
parent 0b8162aa0d
commit e09e9a313e
1 changed files with 2 additions and 0 deletions

View File

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