AP_Mission: Allow Param4 to be uploaded with NaN

By default, QGroundControl will attempt to upload Loiter Unlimited with a NaN in param4.
Given this field could be NaN, we allow it through the parser.

See: https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LOITER_UNLIM
This commit is contained in:
James O'Shannessy 2024-07-08 08:01:53 +10:00 committed by Peter Barker
parent 43bc80ab59
commit 9924462618

View File

@ -964,6 +964,9 @@ MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_in
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
nan_mask = ~(1 << 3); // param 4 can be nan nan_mask = ~(1 << 3); // param 4 can be nan
break; break;
case MAV_CMD_NAV_LOITER_UNLIM:
nan_mask = ~(1 << 3); // param 4 can be nan
break;
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
nan_mask = ~(1 << 3); // param 4 can be nan nan_mask = ~(1 << 3); // param 4 can be nan
break; break;