@ -4500,6 +4500,7 @@ bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command)
case MAV_CMD_DO_SET_ROI:
case MAV_CMD_DO_SET_ROI_LOCATION:
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_DO_REPOSITION:
return true;
default:
return false;