GCS_MAVLink: break out an altitude enumeration mapping function

This commit is contained in:
Peter Barker 2019-02-06 08:46:28 +11:00 committed by Randy Mackay
parent 9105284a7d
commit 64b4e69e34
2 changed files with 25 additions and 0 deletions

View File

@ -284,6 +284,9 @@ protected:
virtual bool in_hil_mode() const { return false; }
bool mavlink_coordinate_frame_to_location_alt_frame(uint8_t coordinate_frame,
Location::ALT_FRAME &frame);
// overridable method to check for packet acceptance. Allows for
// enforcement of GCS sysid
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg);

View File

@ -4314,6 +4314,28 @@ void GCS::passthru_timer(void)
}
}
bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const uint8_t coordinate_frame, Location::ALT_FRAME &frame)
{
switch (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:
frame = Location::ALT_FRAME_ABOVE_HOME;
return true;
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
frame = Location::ALT_FRAME_ABOVE_TERRAIN;
return true;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
frame = Location::ALT_FRAME_ABSOLUTE;
return true;
default:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
gcs().send_text(MAV_SEVERITY_INFO, "Unknown mavlink coordinate frame %u", coordinate_frame);
#endif
return false;
}
}
GCS &gcs()
{