GCS_MAVLink: ensure item being converted is a rally point

This commit is contained in:
Peter Barker 2019-08-01 13:06:58 +10:00 committed by Peter Barker
parent 86c05aba8f
commit 979a9fb679
1 changed files with 3 additions and 0 deletions

View File

@ -50,6 +50,9 @@ bool MissionItemProtocol_Rally::clear_all_items()
MAV_MISSION_RESULT MissionItemProtocol_Rally::convert_MISSION_ITEM_INT_to_RallyLocation(const mavlink_mission_item_int_t &cmd, RallyLocation &ret)
{
if (cmd.command != MAV_CMD_NAV_RALLY_POINT) {
return MAV_MISSION_UNSUPPORTED;
}
if (cmd.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
cmd.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) {
return MAV_MISSION_UNSUPPORTED_FRAME;