AP_Mission: Support storing VTOL_LAND options

This commit is contained in:
Michael du Breuil 2020-07-21 13:15:40 -07:00 committed by WickedShell
parent 6fc7209c69
commit f5ca2c9e7a

View File

@ -1142,6 +1142,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
break;
case MAV_CMD_NAV_VTOL_LAND:
cmd.p1 = (NAV_VTOL_LAND_OPTIONS)packet.param1;
break;
case MAV_CMD_DO_VTOL_TRANSITION:
@ -1637,6 +1638,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
break;
case MAV_CMD_NAV_VTOL_LAND:
packet.param1 = cmd.p1;
break;
case MAV_CMD_DO_VTOL_TRANSITION: