Sub: use altitude frame mapping function

Remove checking for coordinate frames

This is very much NFC.  This change uncovers previous dead code in the
case that we are not ignoring yaw.
This commit is contained in:
Peter Barker 2019-02-12 14:42:36 +11:00 committed by Peter Barker
parent 6d914f8af3
commit dc0ad11f7a

View File

@ -884,16 +884,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
break; break;
} }
// check for supported coordinate frames
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;
}
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE; bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE; bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE; bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
@ -912,29 +902,20 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
if (!check_latlng(packet.lat_int, packet.lon_int)) { if (!check_latlng(packet.lat_int, packet.lon_int)) {
break; break;
} }
Location loc; Location::ALT_FRAME frame;
loc.lat = packet.lat_int; if (!mavlink_coordinate_frame_to_location_alt_frame(packet.coordinate_frame, frame)) {
loc.lng = packet.lon_int; // unknown coordinate frame
loc.alt = packet.alt*100; break;
switch (packet.coordinate_frame) { }
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT const Location loc{
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: packet.lat_int,
loc.relative_alt = true; packet.lon_int,
loc.terrain_alt = false; int32_t(packet.alt*100),
break; frame,
case MAV_FRAME_GLOBAL_TERRAIN_ALT: };
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: if (!loc.get_vector_from_origin_NEU(pos_neu_cm)) {
loc.relative_alt = true;
loc.terrain_alt = true;
break;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
default:
loc.relative_alt = false;
loc.terrain_alt = false;
break; break;
} }
pos_neu_cm = sub.pv_location_to_vector(loc);
} }
if (!pos_ignore && !vel_ignore && acc_ignore) { if (!pos_ignore && !vel_ignore && acc_ignore) {