AP_Mission: Load yaw heading for landing commands

This commit is contained in:
Michael du Breuil 2017-10-03 17:30:41 -07:00 committed by Tom Pittenger
parent 0007e5eb80
commit a0a16b8369
1 changed files with 2 additions and 0 deletions

View File

@ -604,6 +604,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
case MAV_CMD_NAV_LAND: // MAV ID: 21
copy_location = true;
cmd.p1 = packet.param1; // abort target altitude(m) (plane only)
cmd.content.location.flags.loiter_ccw = is_negative(packet.param4); // yaw direction, (plane deepstall only)
break;
case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22
@ -1050,6 +1051,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
case MAV_CMD_NAV_LAND: // MAV ID: 21
copy_location = true;
packet.param1 = cmd.p1; // abort target altitude(m) (plane only)
packet.param4 = cmd.content.location.flags.loiter_ccw ? -1 : 1; // yaw direction, (plane deepstall only)
break;
case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22