AP_Mission: Align with spec better

Location is out of spec for NAV_RETURN_TO_LAUNCH

NAV_LOITER_UNLIM couldn't roundtrip the provided loiter radius
This commit is contained in:
Michael du Breuil 2016-12-05 18:09:58 -07:00 committed by Tom Pittenger
parent 84bdf15203
commit f9acca67d3

View File

@ -575,7 +575,6 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: // MAV ID: 20
copy_location = true;
break;
case MAV_CMD_NAV_LAND: // MAV ID: 21
@ -994,10 +993,9 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
copy_location = true;
packet.param3 = (float)cmd.p1;
if (cmd.content.location.flags.loiter_ccw) {
packet.param3 = -1;
}else{
packet.param3 = 1;
packet.param3 *= -1;
}
break;
@ -1023,7 +1021,6 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: // MAV ID: 20
copy_location = true;
break;
case MAV_CMD_NAV_LAND: // MAV ID: 21