Sub: adjust for location flags being moved out of union

This commit is contained in:
Peter Barker 2019-01-02 13:19:12 +11:00 committed by Peter Barker
parent f1299dc9bf
commit d92f34c3d0

View File

@ -612,7 +612,7 @@ bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
void GCS_MAVLINK_Sub::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
{
// add home alt if needed
if (cmd.content.location.flags.relative_alt) {
if (cmd.content.location.relative_alt) {
cmd.content.location.alt += sub.ahrs.get_home().alt;
}
@ -1038,19 +1038,19 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
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;
loc.relative_alt = true;
loc.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;
loc.relative_alt = true;
loc.terrain_alt = true;
break;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
default:
loc.flags.relative_alt = false;
loc.flags.terrain_alt = false;
loc.relative_alt = false;
loc.terrain_alt = false;
break;
}
pos_neu_cm = sub.pv_location_to_vector(loc);