|
|
|
@ -1385,9 +1385,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
@@ -1385,9 +1385,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check for supported coordinate frames
|
|
|
|
|
if (packet.coordinate_frame != MAV_FRAME_GLOBAL_INT && |
|
|
|
|
if (packet.coordinate_frame != MAV_FRAME_GLOBAL && |
|
|
|
|
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 && |
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) { |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
@ -1421,10 +1423,12 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
@@ -1421,10 +1423,12 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
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; |
|
|
|
|
break; |
|
|
|
|
case MAV_FRAME_GLOBAL: |
|
|
|
|
case MAV_FRAME_GLOBAL_INT: |
|
|
|
|
default: |
|
|
|
|
// Copter does not support navigation to absolute altitudes. This convert the WGS84 altitude
|
|
|
|
|