AP_Mission: Fixes crash in copter when uploading MAV_CMD_NAV_LAND with NaN as p4
Uploading a mission created in QGC with MAV_CMD_NAV_LAND (instead of return to launch) results in crash of copter because p4 is not set.
This commit is contained in:
parent
606c248e69
commit
1794eefd33
@ -915,7 +915,9 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||
|
||||
case MAV_CMD_NAV_LAND: // MAV ID: 21
|
||||
cmd.p1 = packet.param1; // abort target altitude(m) (plane only)
|
||||
cmd.content.location.loiter_ccw = is_negative(packet.param4); // yaw direction, (plane deepstall only)
|
||||
if (!isnan(packet.param4)) {
|
||||
cmd.content.location.loiter_ccw = is_negative(packet.param4); // yaw direction, (plane deepstall only)
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22
|
||||
|
Loading…
Reference in New Issue
Block a user