public List <object> LocationToFence(List <Locationwp> list) { FencePolygon pol = new FencePolygon(); foreach (var locationwp in list) { var plla = new PointLatLngAlt(locationwp); switch (locationwp.id) { case (ushort)MAVLink.MAV_CMD.FENCE_POLYGON_VERTEX_EXCLUSION: { pol.Mode = FencePolygon.PolyType.Exclusive; pol.Points.Add(plla); if (pol.Points.Count == locationwp.p1) { Fences.Add(pol); pol = new FencePolygon(); } } break; case (ushort)MAVLink.MAV_CMD.FENCE_POLYGON_VERTEX_INCLUSION: { pol.Mode = FencePolygon.PolyType.Inclusive; pol.Points.Add(plla); if (pol.Points.Count == locationwp.p1) { Fences.Add(pol); pol = new FencePolygon(); } } break; case (ushort)MAVLink.MAV_CMD.FENCE_CIRCLE_EXCLUSION: { var cir = new FenceCircle() { Mode = FenceCircle.PolyType.Exclusive, Center = plla, Radius = locationwp.p1 }; Fences.Add(cir); } break; case (ushort)MAVLink.MAV_CMD.FENCE_CIRCLE_INCLUSION: { var cir = new FenceCircle() { Mode = FenceCircle.PolyType.Inclusive, Center = plla, Radius = locationwp.p1 }; Fences.Add(cir); } break; case (ushort)MAVLink.MAV_CMD.FENCE_RETURN_POINT: Fences.Add(new FenceReturn() { Return = plla }); break; default: break; } } return(Fences); }
public void DownloadFence(MAVLinkInterface port, Action <int, string> progress = null) { var list = mav_mission.download(port, MAVLink.MAV_MISSION_TYPE.FENCE, progress); FencePolygon pol = new FencePolygon(); foreach (var locationwp in list) { var plla = new PointLatLngAlt(locationwp); switch (locationwp.id) { case (ushort)MAVLink.MAV_CMD.FENCE_POLYGON_VERTEX_EXCLUSION: { pol.Mode = FencePolygon.PolyType.Exclusive; pol.Points.Add(plla); if (pol.Points.Count == locationwp.p1) { Fences.Add(pol); pol = new FencePolygon(); } } break; case (ushort)MAVLink.MAV_CMD.FENCE_POLYGON_VERTEX_INCLUSION: { pol.Mode = FencePolygon.PolyType.Inclusive; pol.Points.Add(plla); if (pol.Points.Count == locationwp.p1) { Fences.Add(pol); pol = new FencePolygon(); } } break; case (ushort)MAVLink.MAV_CMD.FENCE_CIRCLE_EXCLUSION: { var cir = new FenceCircle() { Mode = FenceCircle.PolyType.Exclusive, Center = plla, Radius = locationwp.p1 }; Fences.Add(cir); } break; case (ushort)MAVLink.MAV_CMD.FENCE_CIRCLE_INCLUSION: { var cir = new FenceCircle() { Mode = FenceCircle.PolyType.Inclusive, Center = plla, Radius = locationwp.p1 }; Fences.Add(cir); } break; case (ushort)MAVLink.MAV_CMD.FENCE_RETURN_POINT: Fences.Add(new FenceReturn() { Return = plla }); break; default: break; } } }