public static List <Locationwp> download(MAVLinkInterface port, MAVLink.MAV_MISSION_TYPE type, Action <int, string> progress = null)
        {
            List <Locationwp> commandlist = new List <Locationwp>();

            try
            {
                if (!port.BaseStream.IsOpen)
                {
                    throw new Exception("Please Connect First!");
                }

                bool use_supportfence = (port.MAV.cs.capabilities & (uint)MAVLink.MAV_PROTOCOL_CAPABILITY.MISSION_FENCE) > 0;

                bool use_int = (port.MAV.cs.capabilities & (uint)MAVLink.MAV_PROTOCOL_CAPABILITY.MISSION_INT) > 0;

                if (!use_supportfence && !port.MAV.mavlinkv2 && type != MAVLink.MAV_MISSION_TYPE.MISSION)
                {
                    throw new Exception("Mission type only supported under mavlink2");
                }

                progress?.Invoke(0, "Getting WP count");

                log.Info("Getting WP #");

                int cmdcount = port.getWPCount(type);

                for (ushort a = 0; a < cmdcount; a++)
                {
                    log.Info("Getting WP" + a);
                    progress?.Invoke((a * 100) / cmdcount, "Getting WP " + a);
                    commandlist.Add(port.getWP(a, type));
                }

                port.setWPACK(type);

                progress?.Invoke(100, "Done");

                log.Info("Done");
            }
            catch (Exception ex)
            {
                log.Error(ex);
                throw;
            }

            return(commandlist);
        }