diff --git a/.github/workflows/android.yml b/.github/workflows/android.yml index ecda3b35e7..dfc543c730 100644 --- a/.github/workflows/android.yml +++ b/.github/workflows/android.yml @@ -27,6 +27,7 @@ jobs: !**.apk !**.so !**.aab + !**.dll key: ${{ runner.os }}-buildAAB - name: Build @@ -46,7 +47,7 @@ jobs: $manifest.Save($current.Path + "\ExtLibs\Xamarin\Xamarin.Android\Properties\AndroidManifest.xml") - choco install microsoft-openjdk + choco install microsoft-openjdk --version=11.0.11.9 msbuild -v:m -restore -t:SignAndroidPackage -p:Configuration=Release "ExtLibs\Xamarin\Xamarin.Android\Xamarin.Android.csproj" @@ -102,6 +103,7 @@ jobs: !**.apk !**.so !**.aab + !**.dll key: ${{ runner.os }}-buildAPK - name: Build shell: pwsh @@ -124,7 +126,7 @@ jobs: Set-Content -Path ExtLibs\Xamarin\Xamarin.Android\Xamarin.Android.csproj -Value (Get-Content -Path ExtLibs\Xamarin\Xamarin.Android\Xamarin.Android.csproj -Raw).Replace("true","false") - choco install microsoft-openjdk + choco install microsoft-openjdk --version=11.0.11.9 msbuild -v:m -restore -t:SignAndroidPackage -p:Configuration=Release "ExtLibs\Xamarin\Xamarin.Android\Xamarin.Android.csproj" @@ -135,7 +137,7 @@ jobs: ForEach($i in $apks) { echo $i.FullName Move-Item -path $i.FullName temp.apk - C:\Android\android-sdk\build-tools\29.0.3\zipalign.exe -p -f -v 4 temp.apk $i.FullName + C:\Android\android-sdk\build-tools\31.0.0\zipalign.exe -p -f -v 4 temp.apk $i.FullName Remove-Item temp.apk } @@ -149,6 +151,8 @@ jobs: alias: ${{ secrets.ALIAS }} keyStorePassword: ${{ secrets.KEY_STORE_PASSWORD }} keyPassword: ${{ secrets.KEY_PASSWORD }} + env: + BUILD_TOOLS_VERSION: "31.0.0" - uses: actions/upload-artifact@v2 with: diff --git a/Common.cs b/Common.cs index e4c6fc87f8..7a226e5a4e 100644 --- a/Common.cs +++ b/Common.cs @@ -42,7 +42,7 @@ public static GMapMarker getMAVMarker(MAVState MAV, GMapOverlay overlay = null) itemp.Cog = MAV.cs.groundcourse; itemp.Target = MAV.cs.target_bearing; itemp.Nav_bearing = MAV.cs.nav_bearing; - itemp.Radius = MAV.cs.radius * CurrentState.multiplierdist; + itemp.Radius = (float)CurrentState.fromDistDisplayUnit(MAV.cs.radius); return null; } else if (item is GMapMarkerQuad) @@ -76,7 +76,7 @@ public static GMapMarker getMAVMarker(MAVState MAV, GMapOverlay overlay = null) { return (new GMapMarkerPlane(MAV.sysid - 1, portlocation, MAV.cs.yaw, MAV.cs.groundcourse, MAV.cs.nav_bearing, MAV.cs.target_bearing, - MAV.cs.radius * CurrentState.multiplierdist) + (float)CurrentState.toDistDisplayUnit(MAV.cs.radius)) { ToolTipText = ArduPilot.Common.speechConversion(MAV, "" + Settings.Instance["mapicondesc"]), ToolTipMode = String.IsNullOrEmpty(Settings.Instance["mapicondesc"]) ? MarkerTooltipMode.Never : MarkerTooltipMode.Always, diff --git a/ExtLibs/AltitudeAngelWings/AltitudeAngelWings.csproj b/ExtLibs/AltitudeAngelWings/AltitudeAngelWings.csproj index bb570dd036..1defef05ba 100644 --- a/ExtLibs/AltitudeAngelWings/AltitudeAngelWings.csproj +++ b/ExtLibs/AltitudeAngelWings/AltitudeAngelWings.csproj @@ -22,7 +22,7 @@ - + diff --git a/ExtLibs/AltitudeAngelWings/Clients/Auth/Model/TokenResponseExtensions.cs b/ExtLibs/AltitudeAngelWings/Clients/Auth/Model/TokenResponseExtensions.cs index c2f0eaaaa8..634452f11d 100644 --- a/ExtLibs/AltitudeAngelWings/Clients/Auth/Model/TokenResponseExtensions.cs +++ b/ExtLibs/AltitudeAngelWings/Clients/Auth/Model/TokenResponseExtensions.cs @@ -1,3 +1,4 @@ +using Newtonsoft.Json; using System; using System.Collections.Generic; using System.IdentityModel.Tokens.Jwt; @@ -43,7 +44,7 @@ public static string[] AccessTokenScopes(this TokenResponse tokenResponse) scopes.AddRange(values.Select(item => item.ToString())); break; default: - scopes.Add(JsonExtensions.SerializeToJson(value)); + scopes.Add(JsonConvert.SerializeObject(value)); break; } diff --git a/ExtLibs/ArduPilot/APFirmware.cs b/ExtLibs/ArduPilot/APFirmware.cs index 54f132f5da..9cec657c34 100644 --- a/ExtLibs/ArduPilot/APFirmware.cs +++ b/ExtLibs/ArduPilot/APFirmware.cs @@ -1,281 +1,327 @@ -using Newtonsoft.Json; -using System; -using System.Collections.Generic; -using System.IO; -using System.IO.Compression; -using System.Linq; -using System.Net; -using System.Net.Http; -using System.Text.RegularExpressions; -using System.Threading.Tasks; -using log4net; -using MissionPlanner.Utilities; - -namespace MissionPlanner.ArduPilot -{ - public class APFirmware - { - private static readonly ILog log = - LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); - - - static APFirmware() - { - // bg get list - Task.Run(() => GetList()); - } - public class FirmwareInfo - { - [JsonProperty("board_id", NullValueHandling = NullValueHandling.Ignore)] - public long BoardId { get; set; } - - [JsonProperty("mav-type")] public string MavType { get; set; } - - [JsonProperty("mav-firmware-version-minor", NullValueHandling = NullValueHandling.Ignore)] - public long MavFirmwareVersionMinor { get; set; } - - [JsonProperty("format")] public string Format { get; set; } - - [JsonProperty("url")] public Uri Url { get; set; } - - [JsonProperty("mav-firmware-version-type")] - public string MavFirmwareVersionType { get; set; } - - [JsonProperty("mav-firmware-version-patch", NullValueHandling = NullValueHandling.Ignore)] - public long MavFirmwareVersionPatch { get; set; } - - [JsonProperty("mav-autopilot")] public string MavAutopilot { get; set; } - - [JsonProperty("vehicletype")] public string VehicleType { get; set; } - - [JsonProperty("USBID", NullValueHandling = NullValueHandling.Ignore)] - public string[] Usbid { get; set; } = new string[0]; - - [JsonProperty("platform")] public string Platform { get; set; } - - [JsonProperty("mav-firmware-version", NullValueHandling = NullValueHandling.Ignore)] - public Version MavFirmwareVersion { get; set; } - - [JsonProperty("bootloader_str", NullValueHandling = NullValueHandling.Ignore)] - public string[] BootloaderStr { get; set; } = new string[0]; - - [JsonProperty("git-sha")] public string GitSha { get; set; } - - [JsonProperty("mav-firmware-version-major", NullValueHandling = NullValueHandling.Ignore)] - public long MavFirmwareVersionMajor { get; set; } - - [JsonProperty("mav-firmware-version-str", NullValueHandling = NullValueHandling.Ignore)] - public string MavFirmwareVersionStr { get; set; } - - [JsonProperty("latest")] public long Latest { get; set; } - } - - public class ManifestRoot - { - [JsonProperty("firmware")] public FirmwareInfo[] Firmware { get; set; } - - [JsonProperty("format-version")] public Version FormatVersion { get; set; } - } - - // from generate_manifest.py - with map - public enum RELEASE_TYPES - { - BETA, // beta - DEV, // latest - OFFICIAL // stable - } - - public enum MAV_TYPE - { - ANTENNA_TRACKER, - Copter, - HELICOPTER, - FIXED_WING, - GROUND_ROVER, - SUBMARINE - } - - private static readonly object getListlock = new object(); - - public static void GetList(string url = "https://firmware.ardupilot.org/manifest.json.gz", bool force = false) - { - lock (getListlock) - { - if (force == false && Manifest != null) - return; - - try - { - log.Info(url); - - var client = new HttpClient(); - - if (!String.IsNullOrEmpty(Settings.Instance.UserAgent)) - client.DefaultRequestHeaders.Add("User-Agent", Settings.Instance.UserAgent); - - var manifestgz = client.GetByteArrayAsync(url).GetAwaiter().GetResult(); - var mssrc = new MemoryStream(manifestgz); - var msdest = new MemoryStream(); - GZipStream gz = new GZipStream(mssrc, CompressionMode.Decompress); - gz.CopyTo(msdest); - msdest.Position = 0; - var manifest = new StreamReader(msdest).ReadToEnd(); - - Manifest = JsonConvert.DeserializeObject(manifest); - - log.Info(Manifest.Firmware?.Length); - } - catch (Exception ex) - { - log.Error(ex); - } - } - } - - public static ManifestRoot Manifest { get; set; } - - public static long[] GetBoardID(DeviceInfo device, bool boardidcheck = true) - { - GetList(); - - log.Info("device: "+device.ToJSON()); - - // match the board description - var ans = Manifest.Firmware.Where(a => ( - a.Platform?.ToLower() == device.board?.ToLower() || - a.BootloaderStr.Any(b => b?.ToLower() == device.board?.ToLower()))); - - if (boardidcheck) - ans = ans.Where(a => a.BoardId != 0); - - if (ans.Any()) - { - return ans.Select(a => a.BoardId).Distinct().ToArray(); - } - - if (device.hardwareid == null) - return null; - - // match the vid/pid - Regex vidpid = new Regex("VID_([0-9a-f]+)&PID_([0-9a-f]+)&", RegexOptions.IgnoreCase); - - if (vidpid.IsMatch(device.hardwareid)) - { - var match = vidpid.Match(device.hardwareid); - var lookfor = String.Format("0x{0}/0x{1}", match.Groups[1].Value, match.Groups[2].Value); - - var vidandusbdesc = Manifest.Firmware.Where(a => a.Usbid.Any(b => b.ToLower().Contains(lookfor.ToLower())) && a.BoardId != 0); - - if (vidandusbdesc.Any()) - { - return vidandusbdesc.Select(a => a.BoardId).Distinct().ToArray(); - } - } - - return null; - } - - public static List GetOptions(DeviceInfo device, RELEASE_TYPES? reltype = null, MAV_TYPE? mav_type = null) - { - GetList(); - - log.Info("device: "+device.ToJSON()); - - // match the board description - var ans = Manifest.Firmware.Where(a => ( - a.Platform?.ToLower() == device.board?.ToLower() || - a.BootloaderStr.Any(b => b?.ToLower() == device.board?.ToLower())) && a.BoardId != 0); - - // ignore platform - ans = Manifest.Firmware; - - if (reltype.HasValue) - ans = ans.Where(a => a.MavFirmwareVersionType == reltype.Value.ToString()); - - if (mav_type.HasValue) - ans = ans.Where(a => a.MavType == mav_type.Value.ToString()); - - // "0x26AC/0x0011" - //USB\VID_2DAE&PID_1011&REV_0200 - - // match the vid/pid - Regex vidpid = new Regex("VID_([0-9a-f]+)&PID_([0-9a-f]+)&", RegexOptions.IgnoreCase); - - if (vidpid.IsMatch(device.hardwareid)) - { - var match = vidpid.Match(device.hardwareid); - var lookfor = String.Format("0x{0}/0x{1}", match.Groups[1].Value, match.Groups[2].Value); - - var vidandusbdesc = ans.Where(a => a.Usbid.Any(b => b.ToLower().Contains(lookfor.ToLower()))); - - if (vidandusbdesc.Count() == 0) - return ans.ToList(); - - return vidandusbdesc.ToList(); - } - - return ans.ToList(); - } - - public static List GetRelease(RELEASE_TYPES reltype) - { - GetList(); - - var ans = Manifest.Firmware.Where(a => a.MavFirmwareVersionType == reltype.ToString()); - - ans = ans.GroupBy(b => b.MavType) - .SelectMany(a => - a.Where(b => a.Key == b.MavType && b.MavFirmwareVersion == a.Max(c => c.MavFirmwareVersion)).OrderBy(b=>b.Format)); - /* - ans = ans.GroupBy(b => b.MavType).Select(a => - a.Where(b => a.Key == b.MavType && b.MavFirmwareVersion == a.Max(c => c.MavFirmwareVersion)) - .FirstOrDefault()); - */ - - return ans.ToList(); - } - - public static List GetReleaseNewest(RELEASE_TYPES reltype) - { - // get max version for each mavtype - return GetRelease(reltype).GroupBy(b => b.MavType).Select(a => - a.Where(b => a.Key == b.MavType && b.MavFirmwareVersion == a.Max(c => c.MavFirmwareVersion)) - .FirstOrDefault()).ToList(); - } - - - public static void Test() - { - GetList(); - - var cb = Manifest.Firmware.Where(a => a.Platform == "CubeBlack") - .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); - - var vid = Manifest.Firmware.Where(a => a.Usbid.Any(b => b.ToLower().Contains("ac"))) - .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); - - var bl = Manifest.Firmware.Where(a => a.BootloaderStr.Any(b => b.ToLower().Contains("cubeblack"))) - .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); - - var bid = Manifest.Firmware.Where(a => a.BoardId == 9) - .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); - - - var vidandusbdesc = Manifest.Firmware - .Where(a => a.Usbid.Any(b => b.ToLower().Contains("26ac"))) - .Where(a => a.BootloaderStr.Any(c => c.ToLower().Contains("fmuv3") || c.ToLower().Contains("fmuv3-bl"))) - .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); - - var vidandusbdesc1 = Manifest.Firmware - .Where(a => a.Usbid.Any(b => b.ToLower().Contains("26ac"))) - .Where(a => a.BootloaderStr.Any(c => c.ToLower().Contains("fmuv3") || c.ToLower().Contains("fmuv3-bl"))) - .Where(a => a.MavFirmwareVersionType == "DEV"); - - var vidandusbdesc2 = Manifest.Firmware - .Where(a => a.Usbid.Any(b => b.ToLower().Contains("26ac"))) - .Where(a => a.BootloaderStr.Any(c => c.ToLower().Contains("fmuv3") || c.ToLower().Contains("fmuv3-bl"))) - .Where(a => a.MavFirmwareVersionType == "BETA"); - } - - } -} +using Newtonsoft.Json; +using System; +using System.Collections.Generic; +using System.IO; +using System.IO.Compression; +using System.Linq; +using System.Net; +using System.Net.Http; +using System.Text.RegularExpressions; +using System.Threading.Tasks; +using log4net; +using MissionPlanner.Utilities; + +namespace MissionPlanner.ArduPilot +{ + public class APFirmware + { + private static readonly ILog log = + LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); + + + static APFirmware() + { + // bg get list + Task.Run(() => GetList()); + } + public class FirmwareInfo + { + [JsonProperty("board_id", NullValueHandling = NullValueHandling.Ignore)] + public long BoardId { get; set; } + + [JsonProperty("mav-type")] public string MavType { get; set; } + + [JsonProperty("mav-firmware-version-minor", NullValueHandling = NullValueHandling.Ignore)] + public long MavFirmwareVersionMinor { get; set; } + + [JsonProperty("format")] public string Format { get; set; } + + [JsonProperty("url")] public Uri Url { get; set; } + + [JsonProperty("mav-firmware-version-type")] + public string MavFirmwareVersionType { get; set; } + + [JsonProperty("mav-firmware-version-patch", NullValueHandling = NullValueHandling.Ignore)] + public long MavFirmwareVersionPatch { get; set; } + + [JsonProperty("mav-autopilot")] public string MavAutopilot { get; set; } + + [JsonProperty("vehicletype")] public string VehicleType { get; set; } + + [JsonProperty("USBID", NullValueHandling = NullValueHandling.Ignore)] + public string[] Usbid { get; set; } = new string[0]; + + [JsonProperty("platform")] public string Platform { get; set; } + + [JsonProperty("mav-firmware-version", NullValueHandling = NullValueHandling.Ignore)] + public Version MavFirmwareVersion { get; set; } + + [JsonProperty("bootloader_str", NullValueHandling = NullValueHandling.Ignore)] + public string[] BootloaderStr { get; set; } = new string[0]; + + [JsonProperty("git-sha")] public string GitSha { get; set; } + + [JsonProperty("mav-firmware-version-major", NullValueHandling = NullValueHandling.Ignore)] + public long MavFirmwareVersionMajor { get; set; } + + [JsonProperty("mav-firmware-version-str", NullValueHandling = NullValueHandling.Ignore)] + public string MavFirmwareVersionStr { get; set; } + + [JsonProperty("latest")] public long Latest { get; set; } + } + + public class ManifestRoot + { + [JsonProperty("firmware")] public FirmwareInfo[] Firmware { get; set; } + + [JsonProperty("format-version")] public Version FormatVersion { get; set; } + } + + // from generate_manifest.py - with map + public enum RELEASE_TYPES + { + BETA, // beta + DEV, // latest + OFFICIAL // stable + } + + public enum MAV_TYPE + { + ANTENNA_TRACKER, + Copter, + HELICOPTER, + FIXED_WING, + GROUND_ROVER, + SUBMARINE + } + + private static readonly object getListlock = new object(); + + public static void GetList(string url = "https://firmware.ardupilot.org/manifest.json.gz", bool force = false) + { + lock (getListlock) + { + if (force == false && Manifest != null) + return; + + try + { + log.Info(url); + + var client = new HttpClient(); + + if (!String.IsNullOrEmpty(Settings.Instance.UserAgent)) + client.DefaultRequestHeaders.Add("User-Agent", Settings.Instance.UserAgent); + + var manifestgz = client.GetByteArrayAsync(url).GetAwaiter().GetResult(); + var mssrc = new MemoryStream(manifestgz); + var msdest = new MemoryStream(); + GZipStream gz = new GZipStream(mssrc, CompressionMode.Decompress); + gz.CopyTo(msdest); + msdest.Position = 0; + var manifest = new StreamReader(msdest).ReadToEnd(); + + Manifest = JsonConvert.DeserializeObject(manifest); + + log.Info(Manifest.Firmware?.Length); + + APFirmware.GetListAppend("https://raw.githubusercontent.com/CubePilot/periph-manifest/main/manifest.json"); + } + catch (Exception ex) + { + log.Error(ex); + } + } + } + + public static void GetListAppend(string url, bool force = false) + { + lock (getListlock) + { + try + { + log.Info(url); + + var client = new HttpClient(); + + if (!String.IsNullOrEmpty(Settings.Instance.UserAgent)) + client.DefaultRequestHeaders.Add("User-Agent", Settings.Instance.UserAgent); + + var manifestgz = client.GetByteArrayAsync(url).GetAwaiter().GetResult(); + var mssrc = new MemoryStream(manifestgz); + var msdest = new MemoryStream(); + if (url.EndsWith(".gz")) + { + GZipStream gz = new GZipStream(mssrc, CompressionMode.Decompress); + gz.CopyTo(msdest); + msdest.Position = 0; + } + else + { + mssrc.CopyTo(msdest); + msdest.Position = 0; + } + var manifest = new StreamReader(msdest).ReadToEnd(); + + var Manifest2 = JsonConvert.DeserializeObject(manifest); + + var list = Manifest.Firmware.ToList(); + list.AddRange(Manifest2.Firmware); + Manifest.Firmware = list.ToArray(); + + log.Info(Manifest.Firmware?.Length); + } + catch (Exception ex) + { + log.Error(ex); + } + } + } + + public static ManifestRoot Manifest { get; set; } + + public static long[] GetBoardID(DeviceInfo device, bool boardidcheck = true) + { + GetList(); + + log.Info("device: "+device.ToJSON()); + + // match the board description + var ans = Manifest.Firmware.Where(a => ( + a.Platform?.ToLower() == device.board?.ToLower() || + a.BootloaderStr.Any(b => b?.ToLower() == device.board?.ToLower()))); + + if (boardidcheck) + ans = ans.Where(a => a.BoardId != 0); + + if (ans.Any()) + { + return ans.Select(a => a.BoardId).Distinct().ToArray(); + } + + if (device.hardwareid == null) + return null; + + // match the vid/pid + Regex vidpid = new Regex("VID_([0-9a-f]+)&PID_([0-9a-f]+)&", RegexOptions.IgnoreCase); + + if (vidpid.IsMatch(device.hardwareid)) + { + var match = vidpid.Match(device.hardwareid); + var lookfor = String.Format("0x{0}/0x{1}", match.Groups[1].Value, match.Groups[2].Value); + + var vidandusbdesc = Manifest.Firmware.Where(a => a.Usbid.Any(b => b.ToLower().Contains(lookfor.ToLower())) && a.BoardId != 0); + + if (vidandusbdesc.Any()) + { + return vidandusbdesc.Select(a => a.BoardId).Distinct().ToArray(); + } + } + + return null; + } + + public static List GetOptions(DeviceInfo device, RELEASE_TYPES? reltype = null, MAV_TYPE? mav_type = null) + { + GetList(); + + log.Info("device: "+device.ToJSON()); + + // match the board description + var ans = Manifest.Firmware.Where(a => ( + a.Platform?.ToLower() == device.board?.ToLower() || + a.BootloaderStr.Any(b => b?.ToLower() == device.board?.ToLower())) && a.BoardId != 0); + + // ignore platform + ans = Manifest.Firmware; + + if (reltype.HasValue) + ans = ans.Where(a => a.MavFirmwareVersionType == reltype.Value.ToString()); + + if (mav_type.HasValue) + ans = ans.Where(a => a.MavType == mav_type.Value.ToString()); + + // "0x26AC/0x0011" + //USB\VID_2DAE&PID_1011&REV_0200 + + // match the vid/pid + Regex vidpid = new Regex("VID_([0-9a-f]+)&PID_([0-9a-f]+)&", RegexOptions.IgnoreCase); + + if (vidpid.IsMatch(device.hardwareid)) + { + var match = vidpid.Match(device.hardwareid); + var lookfor = String.Format("0x{0}/0x{1}", match.Groups[1].Value, match.Groups[2].Value); + + var vidandusbdesc = ans.Where(a => a.Usbid.Any(b => b.ToLower().Contains(lookfor.ToLower()))); + + if (vidandusbdesc.Count() == 0) + return ans.ToList(); + + return vidandusbdesc.ToList(); + } + + return ans.ToList(); + } + + public static List GetRelease(RELEASE_TYPES reltype) + { + GetList(); + + var ans = Manifest.Firmware.Where(a => a.MavFirmwareVersionType == reltype.ToString()); + + ans = ans.GroupBy(b => b.MavType) + .SelectMany(a => + a.Where(b => a.Key == b.MavType && b.MavFirmwareVersion == a.Max(c => c.MavFirmwareVersion)).OrderBy(b=>b.Format)); + /* + ans = ans.GroupBy(b => b.MavType).Select(a => + a.Where(b => a.Key == b.MavType && b.MavFirmwareVersion == a.Max(c => c.MavFirmwareVersion)) + .FirstOrDefault()); + */ + + return ans.ToList(); + } + + public static List GetReleaseNewest(RELEASE_TYPES reltype) + { + // get max version for each mavtype + return GetRelease(reltype).GroupBy(b => b.MavType).Select(a => + a.Where(b => a.Key == b.MavType && b.MavFirmwareVersion == a.Max(c => c.MavFirmwareVersion)) + .FirstOrDefault()).ToList(); + } + + + public static void Test() + { + GetList(); + + var cb = Manifest.Firmware.Where(a => a.Platform == "CubeBlack") + .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); + + var vid = Manifest.Firmware.Where(a => a.Usbid.Any(b => b.ToLower().Contains("ac"))) + .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); + + var bl = Manifest.Firmware.Where(a => a.BootloaderStr.Any(b => b.ToLower().Contains("cubeblack"))) + .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); + + var bid = Manifest.Firmware.Where(a => a.BoardId == 9) + .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); + + + var vidandusbdesc = Manifest.Firmware + .Where(a => a.Usbid.Any(b => b.ToLower().Contains("26ac"))) + .Where(a => a.BootloaderStr.Any(c => c.ToLower().Contains("fmuv3") || c.ToLower().Contains("fmuv3-bl"))) + .Where(a => a.MavFirmwareVersionType == "OFFICIAL"); + + var vidandusbdesc1 = Manifest.Firmware + .Where(a => a.Usbid.Any(b => b.ToLower().Contains("26ac"))) + .Where(a => a.BootloaderStr.Any(c => c.ToLower().Contains("fmuv3") || c.ToLower().Contains("fmuv3-bl"))) + .Where(a => a.MavFirmwareVersionType == "DEV"); + + var vidandusbdesc2 = Manifest.Firmware + .Where(a => a.Usbid.Any(b => b.ToLower().Contains("26ac"))) + .Where(a => a.BootloaderStr.Any(c => c.ToLower().Contains("fmuv3") || c.ToLower().Contains("fmuv3-bl"))) + .Where(a => a.MavFirmwareVersionType == "BETA"); + } + + } +} diff --git a/ExtLibs/ArduPilot/CurrentState.cs b/ExtLibs/ArduPilot/CurrentState.cs index b44500cc68..2815f62f85 100644 --- a/ExtLibs/ArduPilot/CurrentState.cs +++ b/ExtLibs/ArduPilot/CurrentState.cs @@ -186,6 +186,9 @@ public bool prearmstatus /// private double Wn_fgo; + //It is true when we got a VFR_HUD message, so it can be used to get climbrate, instead of calculating it from time and alt change. + private bool gotVFR = false; + static CurrentState() { // set default telemrates @@ -313,7 +316,11 @@ public float alt if ((datetime - lastalt).TotalSeconds >= 0.2 && oldalt != alt || lastalt > datetime) { - climbrate = (alt - oldalt) / (float)(datetime - lastalt).TotalSeconds; + //Don't update climbrate if we got a VFR_HUD message, because it is more accurate + if (!gotVFR) + { + climbrate = (alt - oldalt) / (float)(datetime - lastalt).TotalSeconds; + } verticalspeed = (alt - oldalt) / (float)(datetime - lastalt).TotalSeconds; if (float.IsInfinity(_verticalspeed)) _verticalspeed = 0; @@ -1047,7 +1054,7 @@ public float radius get { if (_groundspeed <= 1) return 0; - return (float)(groundspeed * groundspeed / (9.80665 * Math.Tan(roll * MathHelper.deg2rad))); + return (float)toDistDisplayUnit(_groundspeed * _groundspeed / (9.80665 * Math.Tan(roll * MathHelper.deg2rad))); } } [GroupText("Position")] @@ -3498,25 +3505,16 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi var vfr = mavLinkMessage.ToStructure(); groundspeed = vfr.groundspeed; - airspeed = vfr.airspeed; - - //alt = vfr.alt; // this might include baro - ch3percent = vfr.throttle; if (sensors_present.revthrottle && sensors_enabled.revthrottle && sensors_health.revthrottle) if (ch3percent > 0) ch3percent *= -1; - //Console.WriteLine(alt); - - //climbrate = vfr.climb; - - // heading = vfr.heading; - - - //MAVLink.packets[(byte)MAVLink.MSG_NAMES.VFR_HUD); + //This comes from the EKF, so it supposed to be correct + climbrate = vfr.climb; + gotVFR = true; // we have a vfr packet } break; @@ -3646,6 +3644,16 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi } break; + case (uint)MAVLink.MAVLINK_MSG_ID.GIMBAL_DEVICE_ATTITUDE_STATUS: + { + var status = mavLinkMessage.ToStructure(); + Quaternion q = new Quaternion(status.q[0], status.q[1], status.q[2], status.q[3]); + campointa = (float)(q.get_euler_pitch() * (180.0 / Math.PI)); + campointb = (float)(q.get_euler_roll() * (180.0 / Math.PI)); + campointc = (float)(q.get_euler_yaw() * (180.0 / Math.PI)); + if (campointc < 0) campointc += 360; //normalization + } + break; case (uint)MAVLink.MAVLINK_MSG_ID.UAVIONIX_ADSB_OUT_STATUS: { var status = mavLinkMessage.ToStructure(); diff --git a/ExtLibs/ArduPilot/Joystick/JoystickBase.cs b/ExtLibs/ArduPilot/Joystick/JoystickBase.cs index d9332d0ed0..f9576cc82d 100644 --- a/ExtLibs/ArduPilot/Joystick/JoystickBase.cs +++ b/ExtLibs/ArduPilot/Joystick/JoystickBase.cs @@ -42,6 +42,8 @@ public abstract class JoystickBase: IDisposable private Func _Interface; + private Action _LostAction; + protected SynchronizationContext _context; protected MAVLinkInterface Interface @@ -49,6 +51,12 @@ protected MAVLinkInterface Interface get { return _Interface(); } } + public Action LostAction + { + get { if(_LostAction != null) return _LostAction; return delegate () { }; } + set { _LostAction = value; } + } + public JoystickBase(Func currentInterface) { this._Interface = currentInterface; @@ -84,6 +92,14 @@ public JoystickBase(Func currentInterface) { loadconfig(); } + + _LostAction = new Action(delegate + { + _context.Send(delegate + { + CustomMessageBox.Show("Lost Joystick", "Lost Joystick"); + }, null); + }); } public void loadconfig(string joystickconfigbuttonin = "joystickbuttons.xml", @@ -213,6 +229,11 @@ public void setAxis(int channel, joystickaxis axis) JoyChannels[channel].axis = axis; } + public void setExpo(int channel, int expo) + { + JoyChannels[channel].expo = expo; + } + public void setChannel(int channel, joystickaxis axis, bool reverse, int expo) { JoyChannel joy = new JoyChannel(); @@ -604,38 +625,38 @@ void ProcessButtonEvent(JoyButton but, bool buttondown) const int RESXul = 1024; const int RESXl = 1024; const int RESKul = 100; - /* - - ushort expou(ushort x, ushort k) - { - // k*x*x*x + (1-k)*x - return ((ulong)x*x*x/0x10000*k/(RESXul*RESXul/0x10000) + (RESKul-k)*x+RESKul/2)/RESKul; - } - // expo-funktion: - // --------------- - // kmplot - // f(x,k)=exp(ln(x)*k/10) ;P[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20] - // f(x,k)=x*x*x*k/10 + x*(1-k/10) ;P[0,1,2,3,4,5,6,7,8,9,10] - // f(x,k)=x*x*k/10 + x*(1-k/10) ;P[0,1,2,3,4,5,6,7,8,9,10] - // f(x,k)=1+(x-1)*(x-1)*(x-1)*k/10 + (x-1)*(1-k/10) ;P[0,1,2,3,4,5,6,7,8,9,10] - - short expo(short x, short k) - { - if (k == 0) return x; - short y; - bool neg = x < 0; - if (neg) x = -x; - if (k < 0) - { - y = RESXu - expou((ushort)(RESXu - x), (ushort)-k); - } - else - { - y = expou((ushort)x, (ushort)k); - } - return neg ? -y : y; - } - + /* + + ushort expou(ushort x, ushort k) + { + // k*x*x*x + (1-k)*x + return ((ulong)x*x*x/0x10000*k/(RESXul*RESXul/0x10000) + (RESKul-k)*x+RESKul/2)/RESKul; + } + // expo-funktion: + // --------------- + // kmplot + // f(x,k)=exp(ln(x)*k/10) ;P[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20] + // f(x,k)=x*x*x*k/10 + x*(1-k/10) ;P[0,1,2,3,4,5,6,7,8,9,10] + // f(x,k)=x*x*k/10 + x*(1-k/10) ;P[0,1,2,3,4,5,6,7,8,9,10] + // f(x,k)=1+(x-1)*(x-1)*(x-1)*k/10 + (x-1)*(1-k/10) ;P[0,1,2,3,4,5,6,7,8,9,10] + + short expo(short x, short k) + { + if (k == 0) return x; + short y; + bool neg = x < 0; + if (neg) x = -x; + if (k < 0) + { + y = RESXu - expou((ushort)(RESXu - x), (ushort)-k); + } + else + { + y = expou((ushort)x, (ushort)k); + } + return neg ? -y : y; + } + */ @@ -1113,8 +1134,7 @@ protected virtual void mainloop() { log.Error(ex); clearRCOverride(); - _context.Send( - delegate { CustomMessageBox.Show("Lost Joystick", "Lost Joystick"); }, null); + LostAction(); return; } catch (Exception ex) diff --git a/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs b/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs index c6cc37bb13..334e96b105 100644 --- a/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs +++ b/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs @@ -40,15 +40,21 @@ public async Task StartID(MAVState mavState) { Task.Run(async () => { - if ((CameraInformation.flags & (int) MAVLink.CAMERA_CAP_FLAGS.CAPTURE_IMAGE) > 0) + if ((CameraInformation.flags & (int)MAVLink.CAMERA_CAP_FLAGS.CAPTURE_IMAGE) > 0) + { await parent.parent.doCommandAsync(parent.sysid, parent.compid, - MAVLink.MAV_CMD.REQUEST_CAMERA_SETTINGS, 0, 0, 0, 0, 0, 0, 0).ConfigureAwait(false); - if ((CameraInformation.flags & (int) MAVLink.CAMERA_CAP_FLAGS.CAPTURE_VIDEO) > 0) + MAVLink.MAV_CMD.REQUEST_MESSAGE, (int)MAVLink.MAVLINK_MSG_ID.CAMERA_SETTINGS, 0, 0, 0, 0, 0, 0).ConfigureAwait(false); + } + if ((CameraInformation.flags & (int)MAVLink.CAMERA_CAP_FLAGS.CAPTURE_VIDEO) > 0) + { await parent.parent.doCommandAsync(parent.sysid, parent.compid, - MAVLink.MAV_CMD.REQUEST_VIDEO_STREAM_INFORMATION, 0, 0, 0, 0, 0, 0, 0).ConfigureAwait(false); - if ((CameraInformation.flags & (int) MAVLink.CAMERA_CAP_FLAGS.CAPTURE_VIDEO) > 0) + MAVLink.MAV_CMD.REQUEST_MESSAGE, (int)MAVLink.MAVLINK_MSG_ID.VIDEO_STREAM_INFORMATION, 0, 0, 0, 0, 0, 0).ConfigureAwait(false); + } + if ((CameraInformation.flags & (int)MAVLink.CAMERA_CAP_FLAGS.CAPTURE_VIDEO) > 0) + { await parent.parent.doCommandAsync(parent.sysid, parent.compid, - MAVLink.MAV_CMD.REQUEST_STORAGE_INFORMATION, 0, 0, 0, 0, 0, 0, 0).ConfigureAwait(false); + MAVLink.MAV_CMD.REQUEST_MESSAGE, (int)MAVLink.MAVLINK_MSG_ID.STORAGE_INFORMATION, 0, 0, 0, 0, 0, 0).ConfigureAwait(false); + } }); } catch (Exception ex) @@ -100,7 +106,7 @@ await parent.parent.doCommandAsync(parent.sysid, parent.compid, try { var resp = await parent.parent.doCommandAsync(parent.sysid, parent.compid, - MAVLink.MAV_CMD.REQUEST_CAMERA_INFORMATION, 0, 0, 0, 0, 0, 0, 0); + MAVLink.MAV_CMD.REQUEST_MESSAGE, (int)MAVLink.MAVLINK_MSG_ID.CAMERA_INFORMATION, 0, 0, 0, 0, 0, 0); if (resp) { // no use diff --git a/ExtLibs/ArduPilot/parampck.cs b/ExtLibs/ArduPilot/parampck.cs index 969d813843..240eb657d3 100644 --- a/ExtLibs/ArduPilot/parampck.cs +++ b/ExtLibs/ArduPilot/parampck.cs @@ -100,12 +100,12 @@ public static MAVLink.MAVLinkParamList unpack(byte[] data) Array.Copy(data, dataPointer, vdata, 0, mapped.type_len); dataPointer += mapped.type_len; - decimal? default_value = null; + double? default_value = null; if (with_defaults) { if ((flags & 1U) == 0) { - default_value = Convert.ToDecimal(v); + default_value = Convert.ToDouble(v); } else { - default_value = Convert.ToDecimal(decode_value(mapped.type_format, data, dataPointer)); + default_value = Convert.ToDouble(decode_value(mapped.type_format, data, dataPointer)); dataPointer += mapped.type_len; } } diff --git a/ExtLibs/GMap.NET.WindowsForms/GMap.NET.WindowsForms/GMapControl.cs b/ExtLibs/GMap.NET.WindowsForms/GMap.NET.WindowsForms/GMapControl.cs index d774c40dde..0a59227923 100644 --- a/ExtLibs/GMap.NET.WindowsForms/GMap.NET.WindowsForms/GMapControl.cs +++ b/ExtLibs/GMap.NET.WindowsForms/GMap.NET.WindowsForms/GMapControl.cs @@ -1439,7 +1439,6 @@ public void doPaint(IGraphics e) { { e.Clear(EmptyMapBackground); - #if !PocketPC if (MapRenderTransform.HasValue) { @@ -1507,8 +1506,9 @@ public void doPaint(IGraphics e) } #endif DrawMap(e); - OnPaintOverlays(e); } + OnPaintOverlays(e); + } } diff --git a/ExtLibs/LEDBulb/Bulb/Bulb.csproj b/ExtLibs/LEDBulb/Bulb/Bulb.csproj index a7a8e17775..ba380ecabc 100644 --- a/ExtLibs/LEDBulb/Bulb/Bulb.csproj +++ b/ExtLibs/LEDBulb/Bulb/Bulb.csproj @@ -1,100 +1,21 @@ - - + - Debug - x86 - 8.0.30703 - 2.0 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107} + net472 Library - Properties - Bulb - Bulb - v4.7.2 - - - 512 - - - AnyCPU - true - full - false - bin\Debug\ - DEBUG;TRACE - prompt - 4 - false - - - AnyCPU - pdbonly - true - bin\Release\ - TRACE - prompt - 4 - false + false + true + true - - - - - - - - - - - - - - Form - - - Form1.cs - - + Component - - - - Form1.cs - - - ResXFileCodeGenerator - Resources.Designer.cs - Designer - - - True - Resources.resx - True - - - PublicSettingsSingleFileGenerator - Settings.Designer.cs - - - True - Settings.settings - True - - + + - - \ No newline at end of file diff --git a/ExtLibs/Maps/GMapMarkerQuad.cs b/ExtLibs/Maps/GMapMarkerQuad.cs index 537960898a..4f7eb4a9b3 100644 --- a/ExtLibs/Maps/GMapMarkerQuad.cs +++ b/ExtLibs/Maps/GMapMarkerQuad.cs @@ -47,8 +47,8 @@ public override void OnRender(IGraphics g) { var temp = g.Transform; g.TranslateTransform(LocalPosition.X, LocalPosition.Y); - // set centerpoint as 0,0 g.TranslateTransform(-Offset.X, -Offset.Y); + g.RotateTransform(-Overlay.Control.Bearing); // anti NaN try diff --git a/ExtLibs/Mavlink/MAVLinkParam.cs b/ExtLibs/Mavlink/MAVLinkParam.cs index 0f25534a37..1dc4469a63 100644 --- a/ExtLibs/Mavlink/MAVLinkParam.cs +++ b/ExtLibs/Mavlink/MAVLinkParam.cs @@ -33,7 +33,7 @@ public double Value /// /// Default value of parameter as a double, readonly, NaN if not available /// - public readonly decimal? default_value = null; + public readonly double? default_value = null; private MAV_PARAM_TYPE _typeap = 0; public MAV_PARAM_TYPE TypeAP { @@ -82,7 +82,7 @@ private MAVLinkParam() /// /// /// - public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype, decimal? _default_value = null) + public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype, double? _default_value = null) { Name = name; Type = wiretype; @@ -97,7 +97,7 @@ public MAVLinkParam(string name, double value, MAV_PARAM_TYPE wiretype, decimal? /// /// /// - public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE wiretype, MAV_PARAM_TYPE typeap, decimal? _default_value = null) + public MAVLinkParam(string name, byte[] inputwire, MAV_PARAM_TYPE wiretype, MAV_PARAM_TYPE typeap, double? _default_value = null) { Name = name; Type = wiretype; @@ -137,7 +137,7 @@ public double GetValue() } catch { - return (double)float_value; + return Math.Round((double)float_value, 7); } } } diff --git a/ExtLibs/Mavlink/Mavlink.cs b/ExtLibs/Mavlink/Mavlink.cs index c3888f71f6..ed5d08c4cc 100644 --- a/ExtLibs/Mavlink/Mavlink.cs +++ b/ExtLibs/Mavlink/Mavlink.cs @@ -5,7 +5,7 @@ public partial class MAVLink { - public const string MAVLINK_BUILD_DATE = "Sat Jul 15 2023"; + public const string MAVLINK_BUILD_DATE = "Wed Jan 17 2024"; public const string MAVLINK_WIRE_PROTOCOL_VERSION = "2.0"; public const int MAVLINK_MAX_PAYLOAD_LEN = 255; @@ -85,7 +85,7 @@ public partial class MAVLink new message_info(65, "RC_CHANNELS", 118, 42, 42, typeof( mavlink_rc_channels_t )), new message_info(66, "REQUEST_DATA_STREAM", 148, 6, 6, typeof( mavlink_request_data_stream_t )), new message_info(67, "DATA_STREAM", 21, 4, 4, typeof( mavlink_data_stream_t )), - new message_info(69, "MANUAL_CONTROL", 243, 11, 11, typeof( mavlink_manual_control_t )), + new message_info(69, "MANUAL_CONTROL", 243, 11, 30, typeof( mavlink_manual_control_t )), new message_info(70, "RC_CHANNELS_OVERRIDE", 124, 18, 38, typeof( mavlink_rc_channels_override_t )), new message_info(73, "MISSION_ITEM_INT", 38, 37, 38, typeof( mavlink_mission_item_int_t )), new message_info(74, "VFR_HUD", 20, 20, 20, typeof( mavlink_vfr_hud_t )), @@ -112,7 +112,7 @@ public partial class MAVLink new message_info(105, "HIGHRES_IMU", 93, 62, 63, typeof( mavlink_highres_imu_t )), new message_info(106, "OPTICAL_FLOW_RAD", 138, 44, 44, typeof( mavlink_optical_flow_rad_t )), new message_info(107, "HIL_SENSOR", 108, 64, 65, typeof( mavlink_hil_sensor_t )), - new message_info(108, "SIM_STATE", 32, 84, 84, typeof( mavlink_sim_state_t )), + new message_info(108, "SIM_STATE", 32, 84, 92, typeof( mavlink_sim_state_t )), new message_info(109, "RADIO_STATUS", 185, 9, 9, typeof( mavlink_radio_status_t )), new message_info(110, "FILE_TRANSFER_PROTOCOL", 84, 254, 254, typeof( mavlink_file_transfer_protocol_t )), new message_info(111, "TIMESYNC", 34, 16, 16, typeof( mavlink_timesync_t )), @@ -227,7 +227,7 @@ public partial class MAVLink new message_info(256, "SETUP_SIGNING", 71, 42, 42, typeof( mavlink_setup_signing_t )), new message_info(257, "BUTTON_CHANGE", 131, 9, 9, typeof( mavlink_button_change_t )), new message_info(258, "PLAY_TUNE", 187, 32, 232, typeof( mavlink_play_tune_t )), - new message_info(259, "CAMERA_INFORMATION", 92, 235, 235, typeof( mavlink_camera_information_t )), + new message_info(259, "CAMERA_INFORMATION", 92, 235, 236, typeof( mavlink_camera_information_t )), new message_info(260, "CAMERA_SETTINGS", 146, 5, 13, typeof( mavlink_camera_settings_t )), new message_info(261, "STORAGE_INFORMATION", 179, 27, 60, typeof( mavlink_storage_information_t )), new message_info(262, "CAMERA_CAPTURE_STATUS", 12, 18, 22, typeof( mavlink_camera_capture_status_t )), @@ -245,11 +245,12 @@ public partial class MAVLink new message_info(280, "GIMBAL_MANAGER_INFORMATION", 70, 33, 33, typeof( mavlink_gimbal_manager_information_t )), new message_info(281, "GIMBAL_MANAGER_STATUS", 48, 13, 13, typeof( mavlink_gimbal_manager_status_t )), new message_info(282, "GIMBAL_MANAGER_SET_ATTITUDE", 123, 35, 35, typeof( mavlink_gimbal_manager_set_attitude_t )), - new message_info(283, "GIMBAL_DEVICE_INFORMATION", 74, 144, 144, typeof( mavlink_gimbal_device_information_t )), + new message_info(283, "GIMBAL_DEVICE_INFORMATION", 74, 144, 145, typeof( mavlink_gimbal_device_information_t )), new message_info(284, "GIMBAL_DEVICE_SET_ATTITUDE", 99, 32, 32, typeof( mavlink_gimbal_device_set_attitude_t )), - new message_info(285, "GIMBAL_DEVICE_ATTITUDE_STATUS", 137, 40, 40, typeof( mavlink_gimbal_device_attitude_status_t )), - new message_info(286, "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 210, 53, 53, typeof( mavlink_autopilot_state_for_gimbal_device_t )), + new message_info(285, "GIMBAL_DEVICE_ATTITUDE_STATUS", 137, 40, 49, typeof( mavlink_gimbal_device_attitude_status_t )), + new message_info(286, "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 210, 53, 57, typeof( mavlink_autopilot_state_for_gimbal_device_t )), new message_info(287, "GIMBAL_MANAGER_SET_PITCHYAW", 1, 23, 23, typeof( mavlink_gimbal_manager_set_pitchyaw_t )), + new message_info(288, "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 20, 23, 23, typeof( mavlink_gimbal_manager_set_manual_control_t )), new message_info(299, "WIFI_CONFIG_AP", 19, 96, 96, typeof( mavlink_wifi_config_ap_t )), new message_info(301, "AIS_VESSEL", 243, 58, 58, typeof( mavlink_ais_vessel_t )), new message_info(310, "UAVCAN_NODE_STATUS", 28, 17, 17, typeof( mavlink_uavcan_node_status_t )), @@ -268,6 +269,7 @@ public partial class MAVLink new message_info(370, "SMART_BATTERY_INFO", 75, 87, 109, typeof( mavlink_smart_battery_info_t )), new message_info(373, "GENERATOR_STATUS", 117, 42, 42, typeof( mavlink_generator_status_t )), new message_info(375, "ACTUATOR_OUTPUT_STATUS", 251, 140, 140, typeof( mavlink_actuator_output_status_t )), + new message_info(376, "RELAY_STATUS", 199, 8, 8, typeof( mavlink_relay_status_t )), new message_info(385, "TUNNEL", 147, 133, 133, typeof( mavlink_tunnel_t )), new message_info(386, "CAN_FRAME", 132, 16, 16, typeof( mavlink_can_frame_t )), new message_info(387, "CANFD_FRAME", 4, 72, 72, typeof( mavlink_canfd_frame_t )), @@ -324,6 +326,8 @@ public partial class MAVLink new message_info(50003, "HERELINK_TELEM", 62, 19, 19, typeof( mavlink_herelink_telem_t )), new message_info(50004, "CUBEPILOT_FIRMWARE_UPDATE_START", 240, 10, 10, typeof( mavlink_cubepilot_firmware_update_start_t )), new message_info(50005, "CUBEPILOT_FIRMWARE_UPDATE_RESP", 152, 6, 6, typeof( mavlink_cubepilot_firmware_update_resp_t )), + new message_info(52000, "AIRLINK_AUTH", 13, 100, 100, typeof( mavlink_airlink_auth_t )), + new message_info(52001, "AIRLINK_AUTH_RESPONSE", 239, 1, 1, typeof( mavlink_airlink_auth_response_t )), new message_info(26900, "VIDEO_STREAM_INFORMATION99", 222, 246, 246, typeof( mavlink_video_stream_information99_t )), new message_info(0, "HEARTBEAT", 50, 9, 9, typeof( mavlink_heartbeat_t )), @@ -575,6 +579,7 @@ public enum MAVLINK_MSG_ID GIMBAL_DEVICE_ATTITUDE_STATUS = 285, AUTOPILOT_STATE_FOR_GIMBAL_DEVICE = 286, GIMBAL_MANAGER_SET_PITCHYAW = 287, + GIMBAL_MANAGER_SET_MANUAL_CONTROL = 288, WIFI_CONFIG_AP = 299, AIS_VESSEL = 301, UAVCAN_NODE_STATUS = 310, @@ -593,6 +598,7 @@ public enum MAVLINK_MSG_ID SMART_BATTERY_INFO = 370, GENERATOR_STATUS = 373, ACTUATOR_OUTPUT_STATUS = 375, + RELAY_STATUS = 376, TUNNEL = 385, CAN_FRAME = 386, CANFD_FRAME = 387, @@ -649,6 +655,8 @@ public enum MAVLINK_MSG_ID HERELINK_TELEM = 50003, CUBEPILOT_FIRMWARE_UPDATE_START = 50004, CUBEPILOT_FIRMWARE_UPDATE_RESP = 50005, + AIRLINK_AUTH = 52000, + AIRLINK_AUTH_RESPONSE = 52001, VIDEO_STREAM_INFORMATION99 = 26900, HEARTBEAT = 0, } @@ -696,18 +704,6 @@ public enum HEADING_TYPE: int /*default*/ }; - /// - public enum SPEED_TYPE: int /*default*/ - { - /// | - [Description("")] - AIRSPEED=0, - /// | - [Description("")] - GROUNDSPEED=1, - - }; - /// Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries public enum MAV_CMD: ushort { @@ -809,7 +805,7 @@ public enum MAV_CMD: ushort /// Delay mission state machine until within desired distance of next NAV point. |Distance.| Empty| Empty| Empty| Empty| Empty| Empty| [Description("Delay mission state machine until within desired distance of next NAV point.")] CONDITION_DISTANCE=114, - /// Reach a certain target angle. |target angle, 0 is north| angular speed| direction: -1: counter clockwise, 1: clockwise| 0: absolute angle, 1: relative offset| Empty| Empty| Empty| + /// Reach a certain target angle. |target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3.| angular speed| direction: -1: counter clockwise, 0: shortest direction, 1: clockwise| 0: absolute angle, 1: relative offset| Empty| Empty| Empty| [Description("Reach a certain target angle.")] CONDITION_YAW=115, /// NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| @@ -821,8 +817,8 @@ public enum MAV_CMD: ushort /// Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| [Description("Jump to the desired command in the mission list. Repeat this action only the specified number of times")] DO_JUMP=177, - /// Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)| Speed (-1 indicates no change, -2 indicates return to default vehicle speed)| Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)| 0: absolute, 1: relative| Empty| Empty| Empty| - [Description("Change speed and/or throttle set points.")] + /// Change speed and/or throttle set points |Speed type of value set in param2 (such as airspeed, ground speed, and so on)| Speed (-1 indicates no change, -2 indicates return to default vehicle speed)| Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)| 0: absolute, 1: relative| Empty| Empty| Empty| + [Description("Change speed and/or throttle set points")] DO_CHANGE_SPEED=178, /// Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| [Description("Changes the home location either to the current location or a specified location.")] @@ -950,7 +946,7 @@ public enum MAV_CMD: ushort /// Set limits for external control |Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.| Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.| Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.| Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.| Empty| Empty| Empty| [Description("Set limits for external control")] DO_GUIDED_LIMITS=222, - /// Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |0: Stop engine, 1:Start Engine| 0: Warm start, 1:Cold start. Controls use of choke where applicable| Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| Empty| Empty| Empty| Empty| + /// Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |0: Stop engine, 1:Start Engine| 0: Warm start, 1:Cold start. Controls use of choke where applicable| Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| A bitmask of options for engine control| Empty| Empty| Empty| [Description("Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines")] DO_ENGINE_CONTROL=223, /// Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). |Mission sequence value to set| Empty| Empty| Empty| Empty| Empty| Empty| @@ -1054,19 +1050,17 @@ public enum MAV_CMD: ushort /// Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. |Target tag to jump to.| Repeat count.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| [Description("Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number.")] DO_JUMP_TAG=601, - /// High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. |Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| Pitch rate (positive to pitch up).| Yaw rate (positive to yaw to the right).| Gimbal manager flags to use.| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| - [Description("High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager.")] - [Obsolete] + /// Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. |Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| Pitch rate (positive to pitch up).| Yaw rate (positive to yaw to the right).| Gimbal manager flags to use.| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| + [Description("Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. ")] DO_GIMBAL_MANAGER_PITCHYAW=1000, /// Gimbal configuration to set which sysid/compid is in primary and secondary control. |Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Reserved (default:0)| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| [Description("Gimbal configuration to set which sysid/compid is in primary and secondary control.")] - [Obsolete] DO_GIMBAL_MANAGER_CONFIGURE=1001, - /// Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. |Reserved (Set to 0)| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| - [Description("Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values.")] + /// Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a mission| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| + [Description("Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. ")] IMAGE_START_CAPTURE=2000, - /// Stop image capture sequence Use NaN for reserved values. |Reserved (Set to 0)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| - [Description("Stop image capture sequence Use NaN for reserved values.")] + /// Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a mission| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| + [Description("Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. ")] IMAGE_STOP_CAPTURE=2001, /// Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start), -1 to ignore| 1 to reset the trigger sequence, -1 or 0 to ignore| 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| [Description("Enable or disable on-board camera triggering system.")] @@ -2891,46 +2885,52 @@ public enum MAV_MOUNT_MODE: byte }; - /// Gimbal device (low level) capability flags (bitmap) + /// Gimbal device (low level) capability flags (bitmap). [Flags] public enum GIMBAL_DEVICE_CAP_FLAGS: ushort { - /// Gimbal device supports a retracted position | - [Description("Gimbal device supports a retracted position")] + /// Gimbal device supports a retracted position. | + [Description("Gimbal device supports a retracted position.")] HAS_RETRACT=1, - /// Gimbal device supports a horizontal, forward looking position, stabilized | - [Description("Gimbal device supports a horizontal, forward looking position, stabilized")] + /// Gimbal device supports a horizontal, forward looking position, stabilized. | + [Description("Gimbal device supports a horizontal, forward looking position, stabilized.")] HAS_NEUTRAL=2, /// Gimbal device supports rotating around roll axis. | [Description("Gimbal device supports rotating around roll axis.")] HAS_ROLL_AXIS=4, - /// Gimbal device supports to follow a roll angle relative to the vehicle | - [Description("Gimbal device supports to follow a roll angle relative to the vehicle")] + /// Gimbal device supports to follow a roll angle relative to the vehicle. | + [Description("Gimbal device supports to follow a roll angle relative to the vehicle.")] HAS_ROLL_FOLLOW=8, - /// Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized) | - [Description("Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized)")] + /// Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized). | + [Description("Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized).")] HAS_ROLL_LOCK=16, /// Gimbal device supports rotating around pitch axis. | [Description("Gimbal device supports rotating around pitch axis.")] HAS_PITCH_AXIS=32, - /// Gimbal device supports to follow a pitch angle relative to the vehicle | - [Description("Gimbal device supports to follow a pitch angle relative to the vehicle")] + /// Gimbal device supports to follow a pitch angle relative to the vehicle. | + [Description("Gimbal device supports to follow a pitch angle relative to the vehicle.")] HAS_PITCH_FOLLOW=64, - /// Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized) | - [Description("Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized)")] + /// Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized). | + [Description("Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized).")] HAS_PITCH_LOCK=128, /// Gimbal device supports rotating around yaw axis. | [Description("Gimbal device supports rotating around yaw axis.")] HAS_YAW_AXIS=256, - /// Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default) | - [Description("Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)")] + /// Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). | + [Description("Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default).")] HAS_YAW_FOLLOW=512, - /// Gimbal device supports locking to an absolute heading (often this is an option available) | - [Description("Gimbal device supports locking to an absolute heading (often this is an option available)")] + /// Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available). | + [Description("Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available).")] HAS_YAW_LOCK=1024, /// Gimbal device supports yawing/panning infinetely (e.g. using slip disk). | [Description("Gimbal device supports yawing/panning infinetely (e.g. using slip disk).")] SUPPORTS_INFINITE_YAW=2048, + /// Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME. | + [Description("Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME.")] + SUPPORTS_YAW_IN_EARTH_FRAME=4096, + /// Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation. | + [Description("Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation.")] + HAS_RC_INPUTS=8192, }; @@ -2996,18 +2996,33 @@ public enum GIMBAL_DEVICE_FLAGS: ushort /// Set to retracted safe position (no stabilization), takes presedence over all other flags. | [Description("Set to retracted safe position (no stabilization), takes presedence over all other flags.")] RETRACT=1, - /// Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (pitch=yaw=0) but may be any orientation. | - [Description("Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (pitch=yaw=0) but may be any orientation.")] + /// Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation. | + [Description("Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation.")] NEUTRAL=2, - /// Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal. | - [Description("Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal.")] + /// Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. | + [Description("Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.")] ROLL_LOCK=4, - /// Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default. | - [Description("Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default.")] + /// Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. | + [Description("Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.")] PITCH_LOCK=8, - /// Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). | - [Description("Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle).")] + /// Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward). | + [Description("Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward).")] YAW_LOCK=16, + /// Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward). | + [Description("Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward).")] + YAW_IN_VEHICLE_FRAME=32, + /// Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North). | + [Description("Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North).")] + YAW_IN_EARTH_FRAME=64, + /// Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored). | + [Description("Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored).")] + ACCEPTS_YAW_IN_EARTH_FRAME=128, + /// The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored. | + [Description("The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored.")] + RC_EXCLUSIVE=256, + /// The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation. | + [Description("The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation.")] + RC_MIXED=512, }; @@ -3015,21 +3030,36 @@ public enum GIMBAL_DEVICE_FLAGS: ushort [Flags] public enum GIMBAL_MANAGER_FLAGS: uint { - /// Based on GIMBAL_DEVICE_FLAGS_RETRACT | - [Description("Based on GIMBAL_DEVICE_FLAGS_RETRACT")] + /// Based on GIMBAL_DEVICE_FLAGS_RETRACT. | + [Description("Based on GIMBAL_DEVICE_FLAGS_RETRACT.")] RETRACT=1, - /// Based on GIMBAL_DEVICE_FLAGS_NEUTRAL | - [Description("Based on GIMBAL_DEVICE_FLAGS_NEUTRAL")] + /// Based on GIMBAL_DEVICE_FLAGS_NEUTRAL. | + [Description("Based on GIMBAL_DEVICE_FLAGS_NEUTRAL.")] NEUTRAL=2, - /// Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK | - [Description("Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK")] + /// Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK. | + [Description("Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK.")] ROLL_LOCK=4, - /// Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK | - [Description("Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK")] + /// Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK. | + [Description("Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK.")] PITCH_LOCK=8, - /// Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK | - [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK")] + /// Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK. | + [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK.")] YAW_LOCK=16, + /// Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME. | + [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME.")] + YAW_IN_VEHICLE_FRAME=32, + /// Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. | + [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.")] + YAW_IN_EARTH_FRAME=64, + /// Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME. | + [Description("Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME.")] + ACCEPTS_YAW_IN_EARTH_FRAME=128, + /// Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE. | + [Description("Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE.")] + RC_EXCLUSIVE=256, + /// Based on GIMBAL_DEVICE_FLAGS_RC_MIXED. | + [Description("Based on GIMBAL_DEVICE_FLAGS_RC_MIXED.")] + RC_MIXED=512, }; @@ -3052,8 +3082,8 @@ public enum GIMBAL_DEVICE_ERROR_FLAGS: uint /// There is an error with the gimbal power source. | [Description("There is an error with the gimbal power source.")] POWER_ERROR=16, - /// There is an error with the gimbal motor's. | - [Description("There is an error with the gimbal motor's.")] + /// There is an error with the gimbal motors. | + [Description("There is an error with the gimbal motors.")] MOTOR_ERROR=32, /// There is an error with the gimbal's software. | [Description("There is an error with the gimbal's software.")] @@ -3061,9 +3091,12 @@ public enum GIMBAL_DEVICE_ERROR_FLAGS: uint /// There is an error with the gimbal's communication. | [Description("There is an error with the gimbal's communication.")] COMMS_ERROR=128, - /// Gimbal is currently calibrating. | - [Description("Gimbal is currently calibrating.")] + /// Gimbal device is currently calibrating. | + [Description("Gimbal device is currently calibrating.")] CALIBRATION_RUNNING=256, + /// Gimbal device is not assigned to a gimbal manager. | + [Description("Gimbal device is not assigned to a gimbal manager.")] + NO_MANAGER=512, }; @@ -3370,6 +3403,12 @@ public enum MAV_RESULT: byte /// Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. There is no need for the sender to retry the command, but if done during execution, the component will return MAV_RESULT_IN_PROGRESS with an updated progress. | [Description("Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. There is no need for the sender to retry the command, but if done during execution, the component will return MAV_RESULT_IN_PROGRESS with an updated progress.")] IN_PROGRESS=5, + /// Command is only accepted when sent as a COMMAND_LONG. | + [Description("Command is only accepted when sent as a COMMAND_LONG.")] + COMMAND_LONG_ONLY=7, + /// Command is only accepted when sent as a COMMAND_INT. | + [Description("Command is only accepted when sent as a COMMAND_INT.")] + COMMAND_INT_ONLY=8, }; @@ -4181,6 +4220,24 @@ public enum MAV_DO_REPOSITION_FLAGS: int /*default*/ }; + /// Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED + public enum SPEED_TYPE: int /*default*/ + { + /// Airspeed | + [Description("Airspeed")] + AIRSPEED=0, + /// Groundspeed | + [Description("Groundspeed")] + GROUNDSPEED=1, + /// Climb speed | + [Description("Climb speed")] + CLIMB_SPEED=2, + /// Descent speed | + [Description("Descent speed")] + DESCENT_SPEED=3, + + }; + /// Flags in ESTIMATOR_STATUS message [Flags] public enum ESTIMATOR_STATUS_FLAGS: ushort @@ -4663,6 +4720,15 @@ public enum RC_TYPE: int /*default*/ }; + /// Engine control options + public enum ENGINE_CONTROL_OPTIONS: int /*default*/ + { + /// Allow starting the engine once while disarmed | + [Description("Allow starting the engine once while disarmed")] + ALLOW_START_WHILE_DISARMED=1, + + }; + /// Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration. public enum POSITION_TARGET_TYPEMASK: ushort { @@ -6152,6 +6218,19 @@ public enum ICAROUS_FMS_STATE: byte + /// + public enum AIRLINK_AUTH_RESPONSE_TYPE: byte + { + /// Login or password error | + [Description("Login or password error")] + AIRLINK_ERROR_LOGIN_OR_PASS=0, + /// Auth successful | + [Description("Auth successful")] + AIRLINK_AUTH_OK=1, + + }; + + /// Micro air vehicle / autopilot classes. This identifies the individual model. public enum MAV_AUTOPILOT: byte { @@ -15991,13 +16070,13 @@ public static mavlink_data_stream_t PopulateXMLOrder(byte stream_id,ushort messa }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=11)] + /// extensions_start 6 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] /// This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their public struct mavlink_manual_control_t { /// packet ordered constructor - public mavlink_manual_control_t(short x,short y,short z,short r,ushort buttons,byte target) + public mavlink_manual_control_t(short x,short y,short z,short r,ushort buttons,byte target,ushort buttons2,byte enabled_extensions,short s,short t,short aux1,short aux2,short aux3,short aux4,short aux5,short aux6) { this.x = x; this.y = y; @@ -16005,11 +16084,21 @@ public mavlink_manual_control_t(short x,short y,short z,short r,ushort buttons,b this.r = r; this.buttons = buttons; this.target = target; + this.buttons2 = buttons2; + this.enabled_extensions = enabled_extensions; + this.s = s; + this.t = t; + this.aux1 = aux1; + this.aux2 = aux2; + this.aux3 = aux3; + this.aux4 = aux4; + this.aux5 = aux5; + this.aux6 = aux6; } /// packet xml order - public static mavlink_manual_control_t PopulateXMLOrder(byte target,short x,short y,short z,short r,ushort buttons) + public static mavlink_manual_control_t PopulateXMLOrder(byte target,short x,short y,short z,short r,ushort buttons,ushort buttons2,byte enabled_extensions,short s,short t,short aux1,short aux2,short aux3,short aux4,short aux5,short aux6) { var msg = new mavlink_manual_control_t(); @@ -16019,6 +16108,16 @@ public static mavlink_manual_control_t PopulateXMLOrder(byte target,short x,shor msg.z = z; msg.r = r; msg.buttons = buttons; + msg.buttons2 = buttons2; + msg.enabled_extensions = enabled_extensions; + msg.s = s; + msg.t = t; + msg.aux1 = aux1; + msg.aux2 = aux2; + msg.aux3 = aux3; + msg.aux4 = aux4; + msg.aux5 = aux5; + msg.aux6 = aux6; return msg; } @@ -16059,6 +16158,66 @@ public static mavlink_manual_control_t PopulateXMLOrder(byte target,short x,shor [Description("The system to be controlled.")] //[FieldOffset(10)] public byte target; + + /// A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. + [Units("")] + [Description("A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.")] + //[FieldOffset(11)] + public ushort buttons2; + + /// Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6 + [Units("")] + [Description("Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6")] + //[FieldOffset(13)] + public byte enabled_extensions; + + /// Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. + [Units("")] + [Description("Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid.")] + //[FieldOffset(14)] + public short s; + + /// Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. + [Units("")] + [Description("Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid.")] + //[FieldOffset(16)] + public short t; + + /// Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset. + [Units("")] + [Description("Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset.")] + //[FieldOffset(18)] + public short aux1; + + /// Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset. + [Units("")] + [Description("Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset.")] + //[FieldOffset(20)] + public short aux2; + + /// Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset. + [Units("")] + [Description("Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset.")] + //[FieldOffset(22)] + public short aux3; + + /// Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset. + [Units("")] + [Description("Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset.")] + //[FieldOffset(24)] + public short aux4; + + /// Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset. + [Units("")] + [Description("Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset.")] + //[FieldOffset(26)] + public short aux5; + + /// Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset. + [Units("")] + [Description("Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset.")] + //[FieldOffset(28)] + public short aux6; }; @@ -18192,15 +18351,15 @@ public static mavlink_optical_flow_t PopulateXMLOrder(ulong time_usec,byte senso //[FieldOffset(16)] public float ground_distance; - /// Flow in x-sensor direction [dpix] - [Units("[dpix]")] - [Description("Flow in x-sensor direction")] + /// Flow rate around X-axis (deprecated; use flow_rate_x) [rad/s] + [Units("[rad/s]")] + [Description("Flow rate around X-axis (deprecated; use flow_rate_x)")] //[FieldOffset(20)] public short flow_x; - /// Flow in y-sensor direction [dpix] - [Units("[dpix]")] - [Description("Flow in y-sensor direction")] + /// Flow rate around Y-axis (deprecated; use flow_rate_y) [rad/s] + [Units("[rad/s]")] + [Description("Flow rate around Y-axis (deprecated; use flow_rate_y)")] //[FieldOffset(22)] public short flow_y; @@ -19003,13 +19162,13 @@ public static mavlink_hil_sensor_t PopulateXMLOrder(ulong time_usec,float xacc,f }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=84)] + /// extensions_start 21 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=92)] /// Status of simulation environment, if used public struct mavlink_sim_state_t { /// packet ordered constructor - public mavlink_sim_state_t(float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) + public mavlink_sim_state_t(float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd,int lat_int,int lon_int) { this.q1 = q1; this.q2 = q2; @@ -19032,11 +19191,13 @@ public mavlink_sim_state_t(float q1,float q2,float q3,float q4,float roll,float this.vn = vn; this.ve = ve; this.vd = vd; + this.lat_int = lat_int; + this.lon_int = lon_int; } /// packet xml order - public static mavlink_sim_state_t PopulateXMLOrder(float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) + public static mavlink_sim_state_t PopulateXMLOrder(float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd,int lat_int,int lon_int) { var msg = new mavlink_sim_state_t(); @@ -19061,6 +19222,8 @@ public static mavlink_sim_state_t PopulateXMLOrder(float q1,float q2,float q3,fl msg.vn = vn; msg.ve = ve; msg.vd = vd; + msg.lat_int = lat_int; + msg.lon_int = lon_int; return msg; } @@ -19191,6 +19354,18 @@ public static mavlink_sim_state_t PopulateXMLOrder(float q1,float q2,float q3,fl [Description("True velocity in down direction in earth-fixed NED frame")] //[FieldOffset(80)] public float vd; + + /// Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). [degE7] + [Units("[degE7]")] + [Description("Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred).")] + //[FieldOffset(84)] + public int lat_int; + + /// Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). [degE7] + [Units("[degE7]")] + [Description("Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred).")] + //[FieldOffset(88)] + public int lon_int; }; @@ -24978,13 +25153,13 @@ public static mavlink_play_tune_t PopulateXMLOrder(byte target_system,byte targe }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=235)] + /// extensions_start 13 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=236)] /// Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. public struct mavlink_camera_information_t { /// packet ordered constructor - public mavlink_camera_information_t(uint time_boot_ms,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,/*CAMERA_CAP_FLAGS*/uint flags,ushort resolution_h,ushort resolution_v,ushort cam_definition_version,byte[] vendor_name,byte[] model_name,byte lens_id,byte[] cam_definition_uri) + public mavlink_camera_information_t(uint time_boot_ms,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,/*CAMERA_CAP_FLAGS*/uint flags,ushort resolution_h,ushort resolution_v,ushort cam_definition_version,byte[] vendor_name,byte[] model_name,byte lens_id,byte[] cam_definition_uri,byte gimbal_device_id) { this.time_boot_ms = time_boot_ms; this.firmware_version = firmware_version; @@ -24999,11 +25174,12 @@ public mavlink_camera_information_t(uint time_boot_ms,uint firmware_version,floa this.model_name = model_name; this.lens_id = lens_id; this.cam_definition_uri = cam_definition_uri; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,ushort resolution_h,ushort resolution_v,byte lens_id,/*CAMERA_CAP_FLAGS*/uint flags,ushort cam_definition_version,byte[] cam_definition_uri) + public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,ushort resolution_h,ushort resolution_v,byte lens_id,/*CAMERA_CAP_FLAGS*/uint flags,ushort cam_definition_version,byte[] cam_definition_uri,byte gimbal_device_id) { var msg = new mavlink_camera_information_t(); @@ -25020,6 +25196,7 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by msg.flags = flags; msg.cam_definition_version = cam_definition_version; msg.cam_definition_uri = cam_definition_uri; + msg.gimbal_device_id = gimbal_device_id; return msg; } @@ -25105,6 +25282,12 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by //[FieldOffset(95)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=140)] public byte[] cam_definition_uri; + + /// Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. + [Units("")] + [Description("Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.")] + //[FieldOffset(235)] + public byte gimbal_device_id; }; @@ -26317,7 +26500,7 @@ public static mavlink_camera_tracking_geo_status_t PopulateXMLOrder(/*CAMERA_TRA public /*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status; }; - [Obsolete] + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] /// Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. @@ -26405,14 +26588,14 @@ public static mavlink_gimbal_manager_information_t PopulateXMLOrder(uint time_bo //[FieldOffset(28)] public float yaw_max; - /// Gimbal device ID that this gimbal manager is responsible for. + /// Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). [Units("")] - [Description("Gimbal device ID that this gimbal manager is responsible for.")] + [Description("Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] //[FieldOffset(32)] public byte gimbal_device_id; }; - [Obsolete] + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] /// Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz). @@ -26454,15 +26637,15 @@ public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms //[FieldOffset(0)] public uint time_boot_ms; - /// High level gimbal manager flags currently applied. GIMBAL_MANAGER_FLAGS + /// High level gimbal manager flags currently applied. GIMBAL_MANAGER_FLAGS bitmask [Units("")] [Description("High level gimbal manager flags currently applied.")] //[FieldOffset(4)] public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Gimbal device ID that this gimbal manager is responsible for. + /// Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). [Units("")] - [Description("Gimbal device ID that this gimbal manager is responsible for.")] + [Description("Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] //[FieldOffset(8)] public byte gimbal_device_id; @@ -26493,12 +26676,100 @@ public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=144)] + [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] + /// High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + public struct mavlink_gimbal_manager_set_attitude_t + { + /// packet ordered constructor + public mavlink_gimbal_manager_set_attitude_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,byte target_system,byte target_component,byte gimbal_device_id) + { + this.flags = flags; + this.q = q; + this.angular_velocity_x = angular_velocity_x; + this.angular_velocity_y = angular_velocity_y; + this.angular_velocity_z = angular_velocity_z; + this.target_system = target_system; + this.target_component = target_component; + this.gimbal_device_id = gimbal_device_id; + + } + + /// packet xml order + public static mavlink_gimbal_manager_set_attitude_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) + { + var msg = new mavlink_gimbal_manager_set_attitude_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.q = q; + msg.angular_velocity_x = angular_velocity_x; + msg.angular_velocity_y = angular_velocity_y; + msg.angular_velocity_z = angular_velocity_z; + + return msg; + } + + + /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS + [Units("")] + [Description("High level gimbal manager flags to use.")] + //[FieldOffset(0)] + public /*GIMBAL_MANAGER_FLAGS*/uint flags; + + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) + [Units("")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; + + /// X component of angular velocity, positive is rolling to the right, NaN to be ignored. [rad/s] + [Units("[rad/s]")] + [Description("X component of angular velocity, positive is rolling to the right, NaN to be ignored.")] + //[FieldOffset(20)] + public float angular_velocity_x; + + /// Y component of angular velocity, positive is pitching up, NaN to be ignored. [rad/s] + [Units("[rad/s]")] + [Description("Y component of angular velocity, positive is pitching up, NaN to be ignored.")] + //[FieldOffset(24)] + public float angular_velocity_y; + + /// Z component of angular velocity, positive is yawing to the right, NaN to be ignored. [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity, positive is yawing to the right, NaN to be ignored.")] + //[FieldOffset(28)] + public float angular_velocity_z; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(32)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(33)] + public byte target_component; + + /// Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + [Units("")] + [Description("Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).")] + //[FieldOffset(34)] + public byte gimbal_device_id; + }; + + + /// extensions_start 15 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=145)] /// Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.. public struct mavlink_gimbal_device_information_t { /// packet ordered constructor - public mavlink_gimbal_device_information_t(ulong uid,uint time_boot_ms,uint firmware_version,uint hardware_version,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,byte[] vendor_name,byte[] model_name,byte[] custom_name) + public mavlink_gimbal_device_information_t(ulong uid,uint time_boot_ms,uint firmware_version,uint hardware_version,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,byte[] vendor_name,byte[] model_name,byte[] custom_name,byte gimbal_device_id) { this.uid = uid; this.time_boot_ms = time_boot_ms; @@ -26515,11 +26786,12 @@ public mavlink_gimbal_device_information_t(ulong uid,uint time_boot_ms,uint firm this.vendor_name = vendor_name; this.model_name = model_name; this.custom_name = custom_name; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,byte[] custom_name,uint firmware_version,uint hardware_version,ulong uid,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) + public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,byte[] custom_name,uint firmware_version,uint hardware_version,ulong uid,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,byte gimbal_device_id) { var msg = new mavlink_gimbal_device_information_t(); @@ -26538,6 +26810,7 @@ public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boo msg.pitch_max = pitch_max; msg.yaw_min = yaw_min; msg.yaw_max = yaw_max; + msg.gimbal_device_id = gimbal_device_id; return msg; } @@ -26567,39 +26840,39 @@ public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boo //[FieldOffset(16)] public uint hardware_version; - /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] + [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.")] //[FieldOffset(20)] public float roll_min; - /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] + [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.")] //[FieldOffset(24)] public float roll_max; - /// Minimum hardware pitch angle (positive: up, negative: down) [rad] + /// Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] [Units("[rad]")] - [Description("Minimum hardware pitch angle (positive: up, negative: down)")] + [Description("Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] //[FieldOffset(28)] public float pitch_min; - /// Maximum hardware pitch angle (positive: up, negative: down) [rad] + /// Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] [Units("[rad]")] - [Description("Maximum hardware pitch angle (positive: up, negative: down)")] + [Description("Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] //[FieldOffset(32)] public float pitch_max; - /// Minimum hardware yaw angle (positive: to the right, negative: to the left) [rad] + /// Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Minimum hardware yaw angle (positive: to the right, negative: to the left)")] + [Description("Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.")] //[FieldOffset(36)] public float yaw_min; - /// Maximum hardware yaw angle (positive: to the right, negative: to the left) [rad] + /// Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Maximum hardware yaw angle (positive: to the right, negative: to the left)")] + [Description("Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.")] //[FieldOffset(40)] public float yaw_max; @@ -26635,12 +26908,18 @@ public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boo //[FieldOffset(112)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] public byte[] custom_name; + + /// This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. + [Units("")] + [Description("This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.")] + //[FieldOffset(144)] + public byte gimbal_device_id; }; - [Obsolete] + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - /// Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. Angles and rates can be set to NaN according to use case. + /// Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. The quaternion and angular velocities can be set to NaN according to use case. For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. These rules are to ensure backwards compatibility. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. public struct mavlink_gimbal_device_set_attitude_t { /// packet ordered constructor @@ -26673,28 +26952,28 @@ public static mavlink_gimbal_device_set_attitude_t PopulateXMLOrder(byte target_ } - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used) + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored.")] //[FieldOffset(0)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// X component of angular velocity, positive is rolling to the right, NaN to be ignored. [rad/s] + /// X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. [rad/s] [Units("[rad/s]")] - [Description("X component of angular velocity, positive is rolling to the right, NaN to be ignored.")] + [Description("X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(16)] public float angular_velocity_x; - /// Y component of angular velocity, positive is pitching up, NaN to be ignored. [rad/s] + /// Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. [rad/s] [Units("[rad/s]")] - [Description("Y component of angular velocity, positive is pitching up, NaN to be ignored.")] + [Description("Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(20)] public float angular_velocity_y; - /// Z component of angular velocity, positive is yawing to the right, NaN to be ignored. [rad/s] + /// Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. [rad/s] [Units("[rad/s]")] - [Description("Z component of angular velocity, positive is yawing to the right, NaN to be ignored.")] + [Description("Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(24)] public float angular_velocity_z; @@ -26717,14 +26996,14 @@ public static mavlink_gimbal_device_set_attitude_t PopulateXMLOrder(byte target_ public byte target_component; }; - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] - /// Message reporting the status of a gimbal device. This message should be broadcasted by a gimbal device component. The angles encoded in the quaternion are relative to absolute North if the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set (roll: positive is rolling to the right, pitch: positive is pitching up, yaw is turn to the right) or relative to the vehicle heading if the flag is not set. This message should be broadcast at a low regular rate (e.g. 10Hz). + + /// extensions_start 9 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=49)] + /// Message reporting the status of a gimbal device. This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Other conditions of the flags are not allowed. The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN. public struct mavlink_gimbal_device_attitude_status_t { /// packet ordered constructor - public mavlink_gimbal_device_attitude_status_t(uint time_boot_ms,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags,/*GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component) + public mavlink_gimbal_device_attitude_status_t(uint time_boot_ms,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags,/*GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component,float delta_yaw,float delta_yaw_velocity,byte gimbal_device_id) { this.time_boot_ms = time_boot_ms; this.q = q; @@ -26735,11 +27014,14 @@ public mavlink_gimbal_device_attitude_status_t(uint time_boot_ms,float[] q,float this.flags = flags; this.target_system = target_system; this.target_component = target_component; + this.delta_yaw = delta_yaw; + this.delta_yaw_velocity = delta_yaw_velocity; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte target_system,byte target_component,uint time_boot_ms,/*GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags) + public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte target_system,byte target_component,uint time_boot_ms,/*GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags,float delta_yaw,float delta_yaw_velocity,byte gimbal_device_id) { var msg = new mavlink_gimbal_device_attitude_status_t(); @@ -26752,6 +27034,9 @@ public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte targ msg.angular_velocity_y = angular_velocity_y; msg.angular_velocity_z = angular_velocity_z; msg.failure_flags = failure_flags; + msg.delta_yaw = delta_yaw; + msg.delta_yaw_velocity = delta_yaw_velocity; + msg.gimbal_device_id = gimbal_device_id; return msg; } @@ -26763,28 +27048,28 @@ public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte targ //[FieldOffset(0)] public uint time_boot_ms; - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set) + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description.")] //[FieldOffset(4)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// X component of angular velocity (NaN if unknown) [rad/s] + /// X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. [rad/s] [Units("[rad/s]")] - [Description("X component of angular velocity (NaN if unknown)")] + [Description("X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown.")] //[FieldOffset(20)] public float angular_velocity_x; - /// Y component of angular velocity (NaN if unknown) [rad/s] + /// Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. [rad/s] [Units("[rad/s]")] - [Description("Y component of angular velocity (NaN if unknown)")] + [Description("Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown.")] //[FieldOffset(24)] public float angular_velocity_y; - /// Z component of angular velocity (NaN if unknown) [rad/s] + /// Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. [rad/s] [Units("[rad/s]")] - [Description("Z component of angular velocity (NaN if unknown)")] + [Description("Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown.")] //[FieldOffset(28)] public float angular_velocity_z; @@ -26811,16 +27096,34 @@ public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte targ [Description("Component ID")] //[FieldOffset(39)] public byte target_component; + + /// Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. [rad] + [Units("[rad]")] + [Description("Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown.")] + //[FieldOffset(40)] + public float delta_yaw; + + /// Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.")] + //[FieldOffset(44)] + public float delta_yaw_velocity; + + /// This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. + [Units("")] + [Description("This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.")] + //[FieldOffset(48)] + public byte gimbal_device_id; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] - /// Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the gimbal manager to the gimbal device component. The data of this message server for the gimbal's estimator corrections in particular horizon compensation, as well as the autopilot's control intention e.g. feed forward angular control in z-axis. + /// extensions_start 12 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=57)] + /// Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis. public struct mavlink_autopilot_state_for_gimbal_device_t { /// packet ordered constructor - public mavlink_autopilot_state_for_gimbal_device_t(ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,byte target_system,byte target_component,/*MAV_LANDED_STATE*/byte landed_state) + public mavlink_autopilot_state_for_gimbal_device_t(ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,byte target_system,byte target_component,/*MAV_LANDED_STATE*/byte landed_state,float angular_velocity_z) { this.time_boot_us = time_boot_us; this.q = q; @@ -26834,11 +27137,12 @@ public mavlink_autopilot_state_for_gimbal_device_t(ulong time_boot_us,float[] q, this.target_system = target_system; this.target_component = target_component; this.landed_state = landed_state; + this.angular_velocity_z = angular_velocity_z; } /// packet xml order - public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte target_system,byte target_component,ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,/*MAV_LANDED_STATE*/byte landed_state) + public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte target_system,byte target_component,ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,/*MAV_LANDED_STATE*/byte landed_state,float angular_velocity_z) { var msg = new mavlink_autopilot_state_for_gimbal_device_t(); @@ -26854,6 +27158,7 @@ public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte msg.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; msg.estimator_status = estimator_status; msg.landed_state = landed_state; + msg.angular_velocity_z = angular_velocity_z; return msg; } @@ -26872,39 +27177,39 @@ public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// Estimated delay of the attitude data. [us] + /// Estimated delay of the attitude data. 0 if unknown. [us] [Units("[us]")] - [Description("Estimated delay of the attitude data.")] + [Description("Estimated delay of the attitude data. 0 if unknown.")] //[FieldOffset(24)] public uint q_estimated_delay_us; - /// X Speed in NED (North, East, Down). [m/s] + /// X Speed in NED (North, East, Down). NAN if unknown. [m/s] [Units("[m/s]")] - [Description("X Speed in NED (North, East, Down).")] + [Description("X Speed in NED (North, East, Down). NAN if unknown.")] //[FieldOffset(28)] public float vx; - /// Y Speed in NED (North, East, Down). [m/s] + /// Y Speed in NED (North, East, Down). NAN if unknown. [m/s] [Units("[m/s]")] - [Description("Y Speed in NED (North, East, Down).")] + [Description("Y Speed in NED (North, East, Down). NAN if unknown.")] //[FieldOffset(32)] public float vy; - /// Z Speed in NED (North, East, Down). [m/s] + /// Z Speed in NED (North, East, Down). NAN if unknown. [m/s] [Units("[m/s]")] - [Description("Z Speed in NED (North, East, Down).")] + [Description("Z Speed in NED (North, East, Down). NAN if unknown.")] //[FieldOffset(36)] public float vz; - /// Estimated delay of the speed data. [us] + /// Estimated delay of the speed data. 0 if unknown. [us] [Units("[us]")] - [Description("Estimated delay of the speed data.")] + [Description("Estimated delay of the speed data. 0 if unknown.")] //[FieldOffset(40)] public uint v_estimated_delay_us; - /// Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing. [rad/s] + /// Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. [rad/s] [Units("[rad/s]")] - [Description("Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.")] + [Description("Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing.")] //[FieldOffset(44)] public float feed_forward_angular_velocity_z; @@ -26931,22 +27236,28 @@ public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte [Description("The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.")] //[FieldOffset(52)] public /*MAV_LANDED_STATE*/byte landed_state; + + /// Z component of angular velocity in NED (North, East, Down). NaN if unknown. [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity in NED (North, East, Down). NaN if unknown.")] + //[FieldOffset(53)] + public float angular_velocity_z; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] - /// High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. - public struct mavlink_gimbal_manager_set_attitude_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] + /// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. + public struct mavlink_gimbal_manager_set_pitchyaw_t { /// packet ordered constructor - public mavlink_gimbal_manager_set_attitude_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,byte target_system,byte target_component,byte gimbal_device_id) + public mavlink_gimbal_manager_set_pitchyaw_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float pitch,float yaw,float pitch_rate,float yaw_rate,byte target_system,byte target_component,byte gimbal_device_id) { this.flags = flags; - this.q = q; - this.angular_velocity_x = angular_velocity_x; - this.angular_velocity_y = angular_velocity_y; - this.angular_velocity_z = angular_velocity_z; + this.pitch = pitch; + this.yaw = yaw; + this.pitch_rate = pitch_rate; + this.yaw_rate = yaw_rate; this.target_system = target_system; this.target_component = target_component; this.gimbal_device_id = gimbal_device_id; @@ -26954,18 +27265,18 @@ public mavlink_gimbal_manager_set_attitude_t(/*GIMBAL_MANAGER_FLAGS*/uint flags, } /// packet xml order - public static mavlink_gimbal_manager_set_attitude_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) + public static mavlink_gimbal_manager_set_pitchyaw_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate) { - var msg = new mavlink_gimbal_manager_set_attitude_t(); + var msg = new mavlink_gimbal_manager_set_pitchyaw_t(); msg.target_system = target_system; msg.target_component = target_component; msg.flags = flags; msg.gimbal_device_id = gimbal_device_id; - msg.q = q; - msg.angular_velocity_x = angular_velocity_x; - msg.angular_velocity_y = angular_velocity_y; - msg.angular_velocity_z = angular_velocity_z; + msg.pitch = pitch; + msg.yaw = yaw; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; return msg; } @@ -26977,58 +27288,57 @@ public static mavlink_gimbal_manager_set_attitude_t PopulateXMLOrder(byte target //[FieldOffset(0)] public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)")] + /// Pitch angle (positive: up, negative: down, NaN to be ignored). [rad] + [Units("[rad]")] + [Description("Pitch angle (positive: up, negative: down, NaN to be ignored).")] //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; + public float pitch; - /// X component of angular velocity, positive is rolling to the right, NaN to be ignored. [rad/s] - [Units("[rad/s]")] - [Description("X component of angular velocity, positive is rolling to the right, NaN to be ignored.")] - //[FieldOffset(20)] - public float angular_velocity_x; + /// Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). [rad] + [Units("[rad]")] + [Description("Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).")] + //[FieldOffset(8)] + public float yaw; - /// Y component of angular velocity, positive is pitching up, NaN to be ignored. [rad/s] + /// Pitch angular rate (positive: up, negative: down, NaN to be ignored). [rad/s] [Units("[rad/s]")] - [Description("Y component of angular velocity, positive is pitching up, NaN to be ignored.")] - //[FieldOffset(24)] - public float angular_velocity_y; + [Description("Pitch angular rate (positive: up, negative: down, NaN to be ignored).")] + //[FieldOffset(12)] + public float pitch_rate; - /// Z component of angular velocity, positive is yawing to the right, NaN to be ignored. [rad/s] + /// Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). [rad/s] [Units("[rad/s]")] - [Description("Z component of angular velocity, positive is yawing to the right, NaN to be ignored.")] - //[FieldOffset(28)] - public float angular_velocity_z; + [Description("Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).")] + //[FieldOffset(16)] + public float yaw_rate; /// System ID [Units("")] [Description("System ID")] - //[FieldOffset(32)] + //[FieldOffset(20)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(33)] + //[FieldOffset(21)] public byte target_component; /// Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). [Units("")] [Description("Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).")] - //[FieldOffset(34)] + //[FieldOffset(22)] public byte gimbal_device_id; }; - [Obsolete] + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] - /// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. - public struct mavlink_gimbal_manager_set_pitchyaw_t + /// High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + public struct mavlink_gimbal_manager_set_manual_control_t { /// packet ordered constructor - public mavlink_gimbal_manager_set_pitchyaw_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float pitch,float yaw,float pitch_rate,float yaw_rate,byte target_system,byte target_component,byte gimbal_device_id) + public mavlink_gimbal_manager_set_manual_control_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float pitch,float yaw,float pitch_rate,float yaw_rate,byte target_system,byte target_component,byte gimbal_device_id) { this.flags = flags; this.pitch = pitch; @@ -27042,9 +27352,9 @@ public mavlink_gimbal_manager_set_pitchyaw_t(/*GIMBAL_MANAGER_FLAGS*/uint flags, } /// packet xml order - public static mavlink_gimbal_manager_set_pitchyaw_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate) + public static mavlink_gimbal_manager_set_manual_control_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate) { - var msg = new mavlink_gimbal_manager_set_pitchyaw_t(); + var msg = new mavlink_gimbal_manager_set_manual_control_t(); msg.target_system = target_system; msg.target_component = target_component; @@ -27059,33 +27369,33 @@ public static mavlink_gimbal_manager_set_pitchyaw_t PopulateXMLOrder(byte target } - /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS + /// High level gimbal manager flags. GIMBAL_MANAGER_FLAGS [Units("")] - [Description("High level gimbal manager flags to use.")] + [Description("High level gimbal manager flags.")] //[FieldOffset(0)] public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Pitch angle (positive: up, negative: down, NaN to be ignored). [rad] - [Units("[rad]")] - [Description("Pitch angle (positive: up, negative: down, NaN to be ignored).")] + /// Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). + [Units("")] + [Description("Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).")] //[FieldOffset(4)] public float pitch; - /// Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). [rad] - [Units("[rad]")] - [Description("Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).")] + /// Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + [Units("")] + [Description("Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).")] //[FieldOffset(8)] public float yaw; - /// Pitch angular rate (positive: up, negative: down, NaN to be ignored). [rad/s] - [Units("[rad/s]")] - [Description("Pitch angular rate (positive: up, negative: down, NaN to be ignored).")] + /// Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). + [Units("")] + [Description("Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).")] //[FieldOffset(12)] public float pitch_rate; - /// Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). [rad/s] - [Units("[rad/s]")] - [Description("Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).")] + /// Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + [Units("")] + [Description("Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).")] //[FieldOffset(16)] public float yaw_rate; @@ -28699,6 +29009,53 @@ public static mavlink_actuator_output_status_t PopulateXMLOrder(ulong time_usec, }; + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Reports the on/off state of relays, as controlled by MAV_CMD_DO_SET_RELAY. + public struct mavlink_relay_status_t + { + /// packet ordered constructor + public mavlink_relay_status_t(uint time_boot_ms,ushort on,ushort present) + { + this.time_boot_ms = time_boot_ms; + this.on = on; + this.present = present; + + } + + /// packet xml order + public static mavlink_relay_status_t PopulateXMLOrder(uint time_boot_ms,ushort on,ushort present) + { + var msg = new mavlink_relay_status_t(); + + msg.time_boot_ms = time_boot_ms; + msg.on = on; + msg.present = present; + + return msg; + } + + + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; + + /// Relay states. Relay instance numbers are represented as individual bits in this mask by offset. bitmask + [Units("")] + [Description("Relay states. Relay instance numbers are represented as individual bits in this mask by offset.")] + //[FieldOffset(4)] + public ushort on; + + /// Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured. bitmask + [Units("")] + [Description("Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.")] + //[FieldOffset(6)] + public ushort present; + }; + + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=133)] /// Message for transporting 'arbitrary' variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification. @@ -31164,6 +31521,78 @@ public static mavlink_cubepilot_firmware_update_resp_t PopulateXMLOrder(byte tar }; + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=100)] + /// Authorization package + public struct mavlink_airlink_auth_t + { + /// packet ordered constructor + public mavlink_airlink_auth_t(byte[] login,byte[] password) + { + this.login = login; + this.password = password; + + } + + /// packet xml order + public static mavlink_airlink_auth_t PopulateXMLOrder(byte[] login,byte[] password) + { + var msg = new mavlink_airlink_auth_t(); + + msg.login = login; + msg.password = password; + + return msg; + } + + + /// Login + [Units("")] + [Description("Login")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] login; + + /// Password + [Units("")] + [Description("Password")] + //[FieldOffset(50)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] password; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] + /// Response to the authorization request + public struct mavlink_airlink_auth_response_t + { + /// packet ordered constructor + public mavlink_airlink_auth_response_t(/*AIRLINK_AUTH_RESPONSE_TYPE*/byte resp_type) + { + this.resp_type = resp_type; + + } + + /// packet xml order + public static mavlink_airlink_auth_response_t PopulateXMLOrder(/*AIRLINK_AUTH_RESPONSE_TYPE*/byte resp_type) + { + var msg = new mavlink_airlink_auth_response_t(); + + msg.resp_type = resp_type; + + return msg; + } + + + /// Response type AIRLINK_AUTH_RESPONSE_TYPE + [Units("")] + [Description("Response type")] + //[FieldOffset(0)] + public /*AIRLINK_AUTH_RESPONSE_TYPE*/byte resp_type; + }; + + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] /// The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html diff --git a/ExtLibs/Mavlink/mavlink.lua b/ExtLibs/Mavlink/mavlink.lua index 30017a3c44..c6b3556565 100644 --- a/ExtLibs/Mavlink/mavlink.lua +++ b/ExtLibs/Mavlink/mavlink.lua @@ -252,12 +252,13 @@ messageName = { [276] = 'CAMERA_TRACKING_GEO_STATUS', [280] = 'GIMBAL_MANAGER_INFORMATION', [281] = 'GIMBAL_MANAGER_STATUS', + [282] = 'GIMBAL_MANAGER_SET_ATTITUDE', [283] = 'GIMBAL_DEVICE_INFORMATION', [284] = 'GIMBAL_DEVICE_SET_ATTITUDE', [285] = 'GIMBAL_DEVICE_ATTITUDE_STATUS', [286] = 'AUTOPILOT_STATE_FOR_GIMBAL_DEVICE', - [282] = 'GIMBAL_MANAGER_SET_ATTITUDE', [287] = 'GIMBAL_MANAGER_SET_PITCHYAW', + [288] = 'GIMBAL_MANAGER_SET_MANUAL_CONTROL', [299] = 'WIFI_CONFIG_AP', [301] = 'AIS_VESSEL', [310] = 'UAVCAN_NODE_STATUS', @@ -276,6 +277,7 @@ messageName = { [370] = 'SMART_BATTERY_INFO', [373] = 'GENERATOR_STATUS', [375] = 'ACTUATOR_OUTPUT_STATUS', + [376] = 'RELAY_STATUS', [385] = 'TUNNEL', [386] = 'CAN_FRAME', [387] = 'CANFD_FRAME', @@ -308,6 +310,8 @@ messageName = { [50003] = 'HERELINK_TELEM', [50004] = 'CUBEPILOT_FIRMWARE_UPDATE_START', [50005] = 'CUBEPILOT_FIRMWARE_UPDATE_RESP', + [52000] = 'AIRLINK_AUTH', + [52001] = 'AIRLINK_AUTH_RESPONSE', [0] = 'HEARTBEAT', } @@ -326,10 +330,6 @@ local enumEntryName = { [0] = "HEADING_TYPE_COURSE_OVER_GROUND", [1] = "HEADING_TYPE_HEADING", }, - ["SPEED_TYPE"] = { - [0] = "SPEED_TYPE_AIRSPEED", - [1] = "SPEED_TYPE_GROUNDSPEED", - }, ["MAV_CMD"] = { [16] = "MAV_CMD_NAV_WAYPOINT", [17] = "MAV_CMD_NAV_LOITER_UNLIM", @@ -1047,6 +1047,8 @@ local enumEntryName = { [512] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", [1024] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", [2048] = "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", + [4096] = "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", + [8192] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS", }, ["GIMBAL_MANAGER_CAP_FLAGS"] = { [1] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT", @@ -1072,6 +1074,11 @@ local enumEntryName = { [4] = "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", [8] = "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", [16] = "GIMBAL_DEVICE_FLAGS_YAW_LOCK", + [32] = "GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", + [64] = "GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", + [128] = "GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", + [256] = "GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", + [512] = "GIMBAL_DEVICE_FLAGS_RC_MIXED", }, ["GIMBAL_MANAGER_FLAGS"] = { [1] = "GIMBAL_MANAGER_FLAGS_RETRACT", @@ -1079,6 +1086,11 @@ local enumEntryName = { [4] = "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", [8] = "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", [16] = "GIMBAL_MANAGER_FLAGS_YAW_LOCK", + [32] = "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", + [64] = "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", + [128] = "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", + [256] = "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", + [512] = "GIMBAL_MANAGER_FLAGS_RC_MIXED", }, ["GIMBAL_DEVICE_ERROR_FLAGS"] = { [1] = "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", @@ -1090,6 +1102,7 @@ local enumEntryName = { [64] = "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", [128] = "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", [256] = "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", + [512] = "GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", }, ["GRIPPER_ACTIONS"] = { [0] = "GRIPPER_ACTION_RELEASE", @@ -1192,6 +1205,8 @@ local enumEntryName = { [3] = "MAV_RESULT_UNSUPPORTED", [4] = "MAV_RESULT_FAILED", [5] = "MAV_RESULT_IN_PROGRESS", + [7] = "MAV_RESULT_COMMAND_LONG_ONLY", + [8] = "MAV_RESULT_COMMAND_INT_ONLY", }, ["MAV_MISSION_RESULT"] = { [0] = "MAV_MISSION_ACCEPTED", @@ -1460,6 +1475,12 @@ local enumEntryName = { ["MAV_DO_REPOSITION_FLAGS"] = { [1] = "MAV_DO_REPOSITION_FLAGS_CHANGE_MODE", }, + ["SPEED_TYPE"] = { + [0] = "SPEED_TYPE_AIRSPEED", + [1] = "SPEED_TYPE_GROUNDSPEED", + [2] = "SPEED_TYPE_CLIMB_SPEED", + [3] = "SPEED_TYPE_DESCENT_SPEED", + }, ["ESTIMATOR_STATUS_FLAGS"] = { [1] = "ESTIMATOR_ATTITUDE", [2] = "ESTIMATOR_VELOCITY_HORIZ", @@ -1619,6 +1640,9 @@ local enumEntryName = { [0] = "RC_TYPE_SPEKTRUM_DSM2", [1] = "RC_TYPE_SPEKTRUM_DSMX", }, + ["ENGINE_CONTROL_OPTIONS"] = { + [1] = "ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED", + }, ["POSITION_TARGET_TYPEMASK"] = { [1] = "POSITION_TARGET_TYPEMASK_X_IGNORE", [2] = "POSITION_TARGET_TYPEMASK_Y_IGNORE", @@ -2113,6 +2137,10 @@ local enumEntryName = { [4] = "ICAROUS_FMS_STATE_APPROACH", [5] = "ICAROUS_FMS_STATE_LAND", }, + ["AIRLINK_AUTH_RESPONSE_TYPE"] = { + [0] = "AIRLINK_ERROR_LOGIN_OR_PASS", + [1] = "AIRLINK_AUTH_OK", + }, ["MAV_AUTOPILOT"] = { [0] = "MAV_AUTOPILOT_GENERIC", [1] = "MAV_AUTOPILOT_RESERVED", @@ -2518,7 +2546,7 @@ f.cmd_MAV_CMD_DO_SET_MODE_param3 = ProtoField.new("param3: Custom Submode (float f.cmd_MAV_CMD_DO_JUMP_param1 = ProtoField.new("param1: Number (float)", "mavlink_proto.cmd_MAV_CMD_DO_JUMP_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_JUMP_param2 = ProtoField.new("param2: Repeat (float)", "mavlink_proto.cmd_MAV_CMD_DO_JUMP_param2", ftypes.FLOAT, nil) -f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1 = ProtoField.new("param1: Speed Type (float)", "mavlink_proto.cmd_MAV_CMD_DO_CHANGE_SPEED_param1", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1 = ProtoField.new("param1: Speed Type (SPEED_TYPE)", "mavlink_proto.cmd_MAV_CMD_DO_CHANGE_SPEED_param1", ftypes.UINT32, enumEntryName.SPEED_TYPE) f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2 = ProtoField.new("param2: Speed (float)", "mavlink_proto.cmd_MAV_CMD_DO_CHANGE_SPEED_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_CHANGE_SPEED_param3 = ProtoField.new("param3: Throttle (float)", "mavlink_proto.cmd_MAV_CMD_DO_CHANGE_SPEED_param3", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_CHANGE_SPEED_param4 = ProtoField.new("param4: Relative (float)", "mavlink_proto.cmd_MAV_CMD_DO_CHANGE_SPEED_param4", ftypes.FLOAT, nil) @@ -2678,6 +2706,7 @@ f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4 = ProtoField.new("param4: Horiz. Move Limi f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1 = ProtoField.new("param1: Start Engine (float)", "mavlink_proto.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2 = ProtoField.new("param2: Cold Start (float)", "mavlink_proto.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3 = ProtoField.new("param3: Height Delay (float)", "mavlink_proto.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param4 = ProtoField.new("param4: Options (ENGINE_CONTROL_OPTIONS)", "mavlink_proto.cmd_MAV_CMD_DO_ENGINE_CONTROL_param4", ftypes.UINT32, enumEntryName.ENGINE_CONTROL_OPTIONS) f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1 = ProtoField.new("param1: Number (float)", "mavlink_proto.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1", ftypes.FLOAT, nil) @@ -2785,11 +2814,16 @@ f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2 = ProtoField.new("param2: Yaw an f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3 = ProtoField.new("param3: Pitch rate (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4 = ProtoField.new("param4: Yaw rate (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5 = ProtoField.new("param5: Gimbal manager flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", ftypes.UINT32, nil) -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, nil, 1) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 10, nil, 2) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 10, nil, 4) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 10, nil, 8) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 10, nil, 16) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7 = ProtoField.new("param7: Gimbal device ID (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1 = ProtoField.new("param1: sysid primary control (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1", ftypes.FLOAT, nil) @@ -2798,10 +2832,12 @@ f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param3 = ProtoField.new("param3: sysid f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4 = ProtoField.new("param4: compid secondary control (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7 = ProtoField.new("param7: Gimbal device ID (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param1 = ProtoField.new("param1: id (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2 = ProtoField.new("param2: Interval (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3 = ProtoField.new("param3: Total Images (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3", ftypes.FLOAT, nil) f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4 = ProtoField.new("param4: Sequence Number (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_IMAGE_STOP_CAPTURE_param1 = ProtoField.new("param1: id (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_STOP_CAPTURE_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1 = ProtoField.new("param1: Enable (float)", "mavlink_proto.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2 = ProtoField.new("param2: Reset (float)", "mavlink_proto.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2", ftypes.FLOAT, nil) @@ -5522,6 +5558,16 @@ f.MANUAL_CONTROL_y = ProtoField.new("y (int16_t)", "mavlink_proto.MANUAL_CONTROL f.MANUAL_CONTROL_z = ProtoField.new("z (int16_t)", "mavlink_proto.MANUAL_CONTROL_z", ftypes.INT16, nil) f.MANUAL_CONTROL_r = ProtoField.new("r (int16_t)", "mavlink_proto.MANUAL_CONTROL_r", ftypes.INT16, nil) f.MANUAL_CONTROL_buttons = ProtoField.new("buttons (uint16_t)", "mavlink_proto.MANUAL_CONTROL_buttons", ftypes.UINT16, nil) +f.MANUAL_CONTROL_buttons2 = ProtoField.new("buttons2 (uint16_t)", "mavlink_proto.MANUAL_CONTROL_buttons2", ftypes.UINT16, nil) +f.MANUAL_CONTROL_enabled_extensions = ProtoField.new("enabled_extensions (uint8_t)", "mavlink_proto.MANUAL_CONTROL_enabled_extensions", ftypes.UINT8, nil) +f.MANUAL_CONTROL_s = ProtoField.new("s (int16_t)", "mavlink_proto.MANUAL_CONTROL_s", ftypes.INT16, nil) +f.MANUAL_CONTROL_t = ProtoField.new("t (int16_t)", "mavlink_proto.MANUAL_CONTROL_t", ftypes.INT16, nil) +f.MANUAL_CONTROL_aux1 = ProtoField.new("aux1 (int16_t)", "mavlink_proto.MANUAL_CONTROL_aux1", ftypes.INT16, nil) +f.MANUAL_CONTROL_aux2 = ProtoField.new("aux2 (int16_t)", "mavlink_proto.MANUAL_CONTROL_aux2", ftypes.INT16, nil) +f.MANUAL_CONTROL_aux3 = ProtoField.new("aux3 (int16_t)", "mavlink_proto.MANUAL_CONTROL_aux3", ftypes.INT16, nil) +f.MANUAL_CONTROL_aux4 = ProtoField.new("aux4 (int16_t)", "mavlink_proto.MANUAL_CONTROL_aux4", ftypes.INT16, nil) +f.MANUAL_CONTROL_aux5 = ProtoField.new("aux5 (int16_t)", "mavlink_proto.MANUAL_CONTROL_aux5", ftypes.INT16, nil) +f.MANUAL_CONTROL_aux6 = ProtoField.new("aux6 (int16_t)", "mavlink_proto.MANUAL_CONTROL_aux6", ftypes.INT16, nil) f.RC_CHANNELS_OVERRIDE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.RC_CHANNELS_OVERRIDE_target_system", ftypes.UINT8, nil) f.RC_CHANNELS_OVERRIDE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.RC_CHANNELS_OVERRIDE_target_component", ftypes.UINT8, nil) @@ -6017,6 +6063,8 @@ f.SIM_STATE_std_dev_vert = ProtoField.new("std_dev_vert (float)", "mavlink_proto f.SIM_STATE_vn = ProtoField.new("vn (float)", "mavlink_proto.SIM_STATE_vn", ftypes.FLOAT, nil) f.SIM_STATE_ve = ProtoField.new("ve (float)", "mavlink_proto.SIM_STATE_ve", ftypes.FLOAT, nil) f.SIM_STATE_vd = ProtoField.new("vd (float)", "mavlink_proto.SIM_STATE_vd", ftypes.FLOAT, nil) +f.SIM_STATE_lat_int = ProtoField.new("lat_int (int32_t)", "mavlink_proto.SIM_STATE_lat_int", ftypes.INT32, nil) +f.SIM_STATE_lon_int = ProtoField.new("lon_int (int32_t)", "mavlink_proto.SIM_STATE_lon_int", ftypes.INT32, nil) f.RADIO_STATUS_rssi = ProtoField.new("rssi (uint8_t)", "mavlink_proto.RADIO_STATUS_rssi", ftypes.UINT8, nil) f.RADIO_STATUS_remrssi = ProtoField.new("remrssi (uint8_t)", "mavlink_proto.RADIO_STATUS_remrssi", ftypes.UINT8, nil) @@ -8419,6 +8467,7 @@ f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = ProtoFi f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS", "CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS", 12, nil, 2048) f.CAMERA_INFORMATION_cam_definition_version = ProtoField.new("cam_definition_version (uint16_t)", "mavlink_proto.CAMERA_INFORMATION_cam_definition_version", ftypes.UINT16, nil) f.CAMERA_INFORMATION_cam_definition_uri = ProtoField.new("cam_definition_uri (char)", "mavlink_proto.CAMERA_INFORMATION_cam_definition_uri", ftypes.STRING, nil) +f.CAMERA_INFORMATION_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.CAMERA_INFORMATION_gimbal_device_id", ftypes.UINT8, nil) f.CAMERA_SETTINGS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.CAMERA_SETTINGS_time_boot_ms", ftypes.UINT32, nil) f.CAMERA_SETTINGS_mode_id = ProtoField.new("mode_id (CAMERA_MODE)", "mavlink_proto.CAMERA_SETTINGS_mode_id", ftypes.UINT8, enumEntryName.CAMERA_MODE) @@ -9081,17 +9130,44 @@ f.GIMBAL_MANAGER_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlin f.GIMBAL_MANAGER_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_time_boot_ms", ftypes.UINT32, nil) f.GIMBAL_MANAGER_STATUS_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_STATUS_flags", ftypes.UINT32, nil) -f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) -f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) -f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) -f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) -f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) f.GIMBAL_MANAGER_STATUS_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_gimbal_device_id", ftypes.UINT8, nil) f.GIMBAL_MANAGER_STATUS_primary_control_sysid = ProtoField.new("primary_control_sysid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_primary_control_sysid", ftypes.UINT8, nil) f.GIMBAL_MANAGER_STATUS_primary_control_compid = ProtoField.new("primary_control_compid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_primary_control_compid", ftypes.UINT8, nil) f.GIMBAL_MANAGER_STATUS_secondary_control_sysid = ProtoField.new("secondary_control_sysid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_secondary_control_sysid", ftypes.UINT8, nil) f.GIMBAL_MANAGER_STATUS_secondary_control_compid = ProtoField.new("secondary_control_compid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_secondary_control_compid", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_target_system", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_target_component", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) +f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_0", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_1", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_2", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_3", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z", ftypes.FLOAT, nil) + f.GIMBAL_DEVICE_INFORMATION_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_time_boot_ms", ftypes.UINT32, nil) f.GIMBAL_DEVICE_INFORMATION_vendor_name = ProtoField.new("vendor_name (char)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_vendor_name", ftypes.STRING, nil) f.GIMBAL_DEVICE_INFORMATION_model_name = ProtoField.new("model_name (char)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_model_name", ftypes.STRING, nil) @@ -9100,18 +9176,20 @@ f.GIMBAL_DEVICE_INFORMATION_firmware_version = ProtoField.new("firmware_version f.GIMBAL_DEVICE_INFORMATION_hardware_version = ProtoField.new("hardware_version (uint32_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_hardware_version", ftypes.UINT32, nil) f.GIMBAL_DEVICE_INFORMATION_uid = ProtoField.new("uid (uint64_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_uid", ftypes.UINT64, nil) f.GIMBAL_DEVICE_INFORMATION_cap_flags = ProtoField.new("cap_flags (GIMBAL_DEVICE_CAP_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags", ftypes.UINT16, nil) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", "GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", 12, nil, 1) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", "GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", 12, nil, 2) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", 12, nil, 4) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", 12, nil, 8) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", 12, nil, 16) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", 12, nil, 32) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", 12, nil, 64) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", 12, nil, 128) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", 12, nil, 256) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", 12, nil, 512) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", 12, nil, 1024) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", 12, nil, 2048) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", "GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", 14, nil, 1) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", "GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", 14, nil, 2) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", 14, nil, 4) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", 14, nil, 8) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", 14, nil, 16) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", 14, nil, 32) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", 14, nil, 64) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", 14, nil, 128) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", 14, nil, 256) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", 14, nil, 512) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", 14, nil, 1024) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", 14, nil, 2048) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", 14, nil, 4096) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS", 14, nil, 8192) f.GIMBAL_DEVICE_INFORMATION_custom_cap_flags = ProtoField.new("custom_cap_flags (uint16_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_custom_cap_flags", ftypes.UINT16, nil) f.GIMBAL_DEVICE_INFORMATION_roll_min = ProtoField.new("roll_min (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_roll_min", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_INFORMATION_roll_max = ProtoField.new("roll_max (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_roll_max", ftypes.FLOAT, nil) @@ -9119,15 +9197,21 @@ f.GIMBAL_DEVICE_INFORMATION_pitch_min = ProtoField.new("pitch_min (float)", "mav f.GIMBAL_DEVICE_INFORMATION_pitch_max = ProtoField.new("pitch_max (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_pitch_max", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_INFORMATION_yaw_min = ProtoField.new("yaw_min (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_yaw_min", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_yaw_max", ftypes.FLOAT, nil) +f.GIMBAL_DEVICE_INFORMATION_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_gimbal_device_id", ftypes.UINT8, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_target_system", ftypes.UINT8, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_target_component", ftypes.UINT8, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_flags = ProtoField.new("flags (GIMBAL_DEVICE_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags", ftypes.UINT16, nil) -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 5, nil, 1) -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL", 5, nil, 2) -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 5, nil, 4) -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 5, nil, 8) -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK", 5, nil, 16) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RC_MIXED", "GIMBAL_DEVICE_FLAGS_RC_MIXED", 10, nil, 512) f.GIMBAL_DEVICE_SET_ATTITUDE_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_q_0", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_q_1", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_q_2", ftypes.FLOAT, nil) @@ -9140,11 +9224,16 @@ f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_system = ProtoField.new("target_system (u f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_target_component", ftypes.UINT8, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_time_boot_ms", ftypes.UINT32, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags = ProtoField.new("flags (GIMBAL_DEVICE_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags", ftypes.UINT16, nil) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 5, nil, 1) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL", 5, nil, 2) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 5, nil, 4) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 5, nil, 8) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK", 5, nil, 16) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RC_MIXED", "GIMBAL_DEVICE_FLAGS_RC_MIXED", 10, nil, 512) f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_q_0", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_q_1", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_q_2", ftypes.FLOAT, nil) @@ -9153,15 +9242,19 @@ f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_x = ProtoField.new("angular_vel f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_y", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_z", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags = ProtoField.new("failure_flags (GIMBAL_DEVICE_ERROR_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags", ftypes.UINT32, nil) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", 9, nil, 1) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", 9, nil, 2) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", 9, nil, 4) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", 9, nil, 8) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", 9, nil, 16) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", 9, nil, 32) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", 9, nil, 64) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", 9, nil, 128) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", 9, nil, 256) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", 10, nil, 1) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", 10, nil, 2) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", 10, nil, 4) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", 10, nil, 8) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", 10, nil, 16) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", 10, nil, 32) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", 10, nil, 64) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", 10, nil, 128) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", 10, nil, 256) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", "GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", 10, nil, 512) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw = ProtoField.new("delta_yaw (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw", ftypes.FLOAT, nil) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw_velocity = ProtoField.new("delta_yaw_velocity (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw_velocity", ftypes.FLOAT, nil) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_gimbal_device_id", ftypes.UINT8, nil) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_system", ftypes.UINT8, nil) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_component", ftypes.UINT8, nil) @@ -9190,38 +9283,46 @@ f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_PRED_POS_HORI f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_GPS_GLITCH = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_GPS_GLITCH", "ESTIMATOR_GPS_GLITCH", 12, nil, 1024) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_ACCEL_ERROR = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_ACCEL_ERROR", "ESTIMATOR_ACCEL_ERROR", 12, nil, 2048) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state = ProtoField.new("landed_state (MAV_LANDED_STATE)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state", ftypes.UINT8, enumEntryName.MAV_LANDED_STATE) - -f.GIMBAL_MANAGER_SET_ATTITUDE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_target_system", ftypes.UINT8, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_target_component", ftypes.UINT8, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags", ftypes.UINT32, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) -f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id", ftypes.UINT8, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_0", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_1", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_2", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_3", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z", ftypes.FLOAT, nil) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_angular_velocity_z", ftypes.FLOAT, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_target_system", ftypes.UINT8, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_target_component", ftypes.UINT8, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags", ftypes.UINT32, nil) -f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) -f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) -f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) -f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) -f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) f.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id", ftypes.UINT8, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_pitch = ProtoField.new("pitch (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_pitch", ftypes.FLOAT, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_yaw = ProtoField.new("yaw (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_yaw", ftypes.FLOAT, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate = ProtoField.new("pitch_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate", ftypes.FLOAT, nil) f.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate = ProtoField.new("yaw_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_system", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_component", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_gimbal_device_id", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch = ProtoField.new("pitch (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw = ProtoField.new("yaw (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch_rate = ProtoField.new("pitch_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch_rate", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw_rate = ProtoField.new("yaw_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw_rate", ftypes.FLOAT, nil) + f.WIFI_CONFIG_AP_ssid = ProtoField.new("ssid (char)", "mavlink_proto.WIFI_CONFIG_AP_ssid", ftypes.STRING, nil) f.WIFI_CONFIG_AP_password = ProtoField.new("password (char)", "mavlink_proto.WIFI_CONFIG_AP_password", ftypes.STRING, nil) @@ -9662,6 +9763,10 @@ f.ACTUATOR_OUTPUT_STATUS_actuator_29 = ProtoField.new("actuator[29] (float)", "m f.ACTUATOR_OUTPUT_STATUS_actuator_30 = ProtoField.new("actuator[30] (float)", "mavlink_proto.ACTUATOR_OUTPUT_STATUS_actuator_30", ftypes.FLOAT, nil) f.ACTUATOR_OUTPUT_STATUS_actuator_31 = ProtoField.new("actuator[31] (float)", "mavlink_proto.ACTUATOR_OUTPUT_STATUS_actuator_31", ftypes.FLOAT, nil) +f.RELAY_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.RELAY_STATUS_time_boot_ms", ftypes.UINT32, nil) +f.RELAY_STATUS_on = ProtoField.new("on (uint16_t)", "mavlink_proto.RELAY_STATUS_on", ftypes.UINT16, nil) +f.RELAY_STATUS_present = ProtoField.new("present (uint16_t)", "mavlink_proto.RELAY_STATUS_present", ftypes.UINT16, nil) + f.TUNNEL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.TUNNEL_target_system", ftypes.UINT8, nil) f.TUNNEL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.TUNNEL_target_component", ftypes.UINT8, nil) f.TUNNEL_payload_type = ProtoField.new("payload_type (MAV_TUNNEL_PAYLOAD_TYPE)", "mavlink_proto.TUNNEL_payload_type", ftypes.UINT16, enumEntryName.MAV_TUNNEL_PAYLOAD_TYPE) @@ -10598,6 +10703,11 @@ f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_system = ProtoField.new("target_system ( f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_component", ftypes.UINT8, nil) f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset = ProtoField.new("offset (uint32_t)", "mavlink_proto.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset", ftypes.UINT32, nil) +f.AIRLINK_AUTH_login = ProtoField.new("login (char)", "mavlink_proto.AIRLINK_AUTH_login", ftypes.STRING, nil) +f.AIRLINK_AUTH_password = ProtoField.new("password (char)", "mavlink_proto.AIRLINK_AUTH_password", ftypes.STRING, nil) + +f.AIRLINK_AUTH_RESPONSE_resp_type = ProtoField.new("resp_type (AIRLINK_AUTH_RESPONSE_TYPE)", "mavlink_proto.AIRLINK_AUTH_RESPONSE_resp_type", ftypes.UINT8, enumEntryName.AIRLINK_AUTH_RESPONSE_TYPE) + f.HEARTBEAT_type = ProtoField.new("type (MAV_TYPE)", "mavlink_proto.HEARTBEAT_type", ftypes.UINT8, enumEntryName.MAV_TYPE) f.HEARTBEAT_autopilot = ProtoField.new("autopilot (MAV_AUTOPILOT)", "mavlink_proto.HEARTBEAT_autopilot", ftypes.UINT8, enumEntryName.MAV_AUTOPILOT) f.HEARTBEAT_base_mode = ProtoField.new("base_mode (MAV_MODE_FLAG)", "mavlink_proto.HEARTBEAT_base_mode", ftypes.UINT8, nil) @@ -10713,6 +10823,8 @@ function dissect_flags_GIMBAL_DEVICE_CAP_FLAGS(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS"], tvbrange, value) end -- dissect flag field function dissect_flags_GIMBAL_MANAGER_CAP_FLAGS(tree, name, tvbrange, value) @@ -10740,6 +10852,11 @@ function dissect_flags_GIMBAL_DEVICE_FLAGS(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_RC_MIXED"], tvbrange, value) end -- dissect flag field function dissect_flags_GIMBAL_MANAGER_FLAGS(tree, name, tvbrange, value) @@ -10748,6 +10865,11 @@ function dissect_flags_GIMBAL_MANAGER_FLAGS(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_RC_MIXED"], tvbrange, value) end -- dissect flag field function dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, tvbrange, value) @@ -10760,6 +10882,7 @@ function dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR"], tvbrange, value) tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER"], tvbrange, value) end -- dissect flag field function dissect_flags_AUTOTUNE_AXIS(tree, name, tvbrange, value) @@ -19142,9 +19265,9 @@ end -- dissect payload of message type MANUAL_CONTROL function payload_fns.payload_69(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 11 > limit) then + if (offset + 30 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 11) + padded:set_size(offset + 30) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -19167,6 +19290,36 @@ function payload_fns.payload_69(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 8, 2) value = tvbrange:le_uint() subtree = tree:add_le(f.MANUAL_CONTROL_buttons, tvbrange, value) + tvbrange = padded(offset + 11, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_CONTROL_buttons2, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_CONTROL_enabled_extensions, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_s, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_t, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_aux1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_aux2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_aux3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_aux4, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_aux5, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_aux6, tvbrange, value) end -- dissect payload of message type RC_CHANNELS_OVERRIDE function payload_fns.payload_70(buffer, tree, msgid, offset, limit, pinfo) @@ -22965,7 +23118,7 @@ function payload_fns.payload_75_cmd223(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) @@ -24657,7 +24810,7 @@ function payload_fns.payload_75_cmd2000(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, tvbrange, value) @@ -24707,7 +24860,7 @@ function payload_fns.payload_75_cmd2001(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_STOP_CAPTURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -31790,7 +31943,7 @@ function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -33278,7 +33431,7 @@ function payload_fns.payload_76_cmd2000(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, tvbrange, value) @@ -33322,7 +33475,7 @@ function payload_fns.payload_76_cmd2001(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_STOP_CAPTURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -37934,9 +38087,9 @@ end -- dissect payload of message type SIM_STATE function payload_fns.payload_108(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 84 > limit) then + if (offset + 92 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 84) + padded:set_size(offset + 92) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -38004,6 +38157,12 @@ function payload_fns.payload_108(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 80, 4) value = tvbrange:le_float() subtree = tree:add_le(f.SIM_STATE_vd, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SIM_STATE_lat_int, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SIM_STATE_lon_int, tvbrange, value) end -- dissect payload of message type RADIO_STATUS function payload_fns.payload_109(buffer, tree, msgid, offset, limit, pinfo) @@ -45220,9 +45379,9 @@ end -- dissect payload of message type CAMERA_INFORMATION function payload_fns.payload_259(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 235 > limit) then + if (offset + 236 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 235) + padded:set_size(offset + 236) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -45453,6 +45612,9 @@ function payload_fns.payload_259(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 95, 140) value = tvbrange:string() subtree = tree:add_le(f.CAMERA_INFORMATION_cam_definition_uri, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_gimbal_device_id, tvbrange, value) end -- dissect payload of message type CAMERA_SETTINGS function payload_fns.payload_260(buffer, tree, msgid, offset, limit, pinfo) @@ -47519,12 +47681,57 @@ function payload_fns.payload_281(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_secondary_control_compid, tvbrange, value) end +-- dissect payload of message type GIMBAL_MANAGER_SET_ATTITUDE +function payload_fns.payload_282(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 35 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 35) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_system, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_ATTITUDE_flags", tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z, tvbrange, value) +end -- dissect payload of message type GIMBAL_DEVICE_INFORMATION function payload_fns.payload_283(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 144 > limit) then + if (offset + 145 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 144) + padded:set_size(offset + 145) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -47575,6 +47782,9 @@ function payload_fns.payload_283(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 40, 4) value = tvbrange:le_float() subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_yaw_max, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_gimbal_device_id, tvbrange, value) end -- dissect payload of message type GIMBAL_DEVICE_SET_ATTITUDE function payload_fns.payload_284(buffer, tree, msgid, offset, limit, pinfo) @@ -47621,9 +47831,9 @@ end -- dissect payload of message type GIMBAL_DEVICE_ATTITUDE_STATUS function payload_fns.payload_285(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 40 > limit) then + if (offset + 49 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 40) + padded:set_size(offset + 49) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -47666,13 +47876,22 @@ function payload_fns.payload_285(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags, tvbrange, value) dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(subtree, "GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags", tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw_velocity, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_gimbal_device_id, tvbrange, value) end -- dissect payload of message type AUTOPILOT_STATE_FOR_GIMBAL_DEVICE function payload_fns.payload_286(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 53 > limit) then + if (offset + 57 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 53) + padded:set_size(offset + 57) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -47723,54 +47942,48 @@ function payload_fns.payload_286(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 52, 1) value = tvbrange:le_uint() subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state, tvbrange, value) + tvbrange = padded(offset + 53, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_angular_velocity_z, tvbrange, value) end --- dissect payload of message type GIMBAL_MANAGER_SET_ATTITUDE -function payload_fns.payload_282(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type GIMBAL_MANAGER_SET_PITCHYAW +function payload_fns.payload_287(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 35 > limit) then + if (offset + 23 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 35) + padded:set_size(offset + 23) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 32, 1) + tvbrange = padded(offset + 20, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_system, tvbrange, value) - tvbrange = padded(offset + 33, 1) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_system, tvbrange, value) + tvbrange = padded(offset + 21, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_component, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_component, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_flags, tvbrange, value) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_ATTITUDE_flags", tvbrange, value) - tvbrange = padded(offset + 34, 1) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_PITCHYAW_flags", tvbrange, value) + tvbrange = padded(offset + 22, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_0, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_pitch, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_1, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_2, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_3, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate, tvbrange, value) end --- dissect payload of message type GIMBAL_MANAGER_SET_PITCHYAW -function payload_fns.payload_287(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type GIMBAL_MANAGER_SET_MANUAL_CONTROL +function payload_fns.payload_288(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 23 > limit) then padded = buffer(0, limit):bytes() @@ -47781,29 +47994,29 @@ function payload_fns.payload_287(buffer, tree, msgid, offset, limit, pinfo) end tvbrange = padded(offset + 20, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_system, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_system, tvbrange, value) tvbrange = padded(offset + 21, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_component, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_component, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_flags, tvbrange, value) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_PITCHYAW_flags", tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags", tvbrange, value) tvbrange = padded(offset + 22, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_gimbal_device_id, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_pitch, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch_rate, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw_rate, tvbrange, value) end -- dissect payload of message type WIFI_CONFIG_AP function payload_fns.payload_299(buffer, tree, msgid, offset, limit, pinfo) @@ -49140,6 +49353,26 @@ function payload_fns.payload_375(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_float() subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_31, tvbrange, value) end +-- dissect payload of message type RELAY_STATUS +function payload_fns.payload_376(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 8 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 8) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RELAY_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RELAY_STATUS_on, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RELAY_STATUS_present, tvbrange, value) +end -- dissect payload of message type TUNNEL function payload_fns.payload_385(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -52107,6 +52340,37 @@ function payload_fns.payload_50005(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset, tvbrange, value) end +-- dissect payload of message type AIRLINK_AUTH +function payload_fns.payload_52000(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 100 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 100) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 50) + value = tvbrange:string() + subtree = tree:add_le(f.AIRLINK_AUTH_login, tvbrange, value) + tvbrange = padded(offset + 50, 50) + value = tvbrange:string() + subtree = tree:add_le(f.AIRLINK_AUTH_password, tvbrange, value) +end +-- dissect payload of message type AIRLINK_AUTH_RESPONSE +function payload_fns.payload_52001(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 1 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 1) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIRLINK_AUTH_RESPONSE_resp_type, tvbrange, value) +end -- dissect payload of message type HEARTBEAT function payload_fns.payload_0(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -52233,9 +52497,9 @@ function mavlink_proto.dissector(buffer,pinfo,tree) offset = offset + 1 else -- handle truncated header - local hsize = buffer:len() - 2 - offset - subtree:add(f.rawheader, buffer(offset, hsize)) - offset = offset + hsize + pinfo.desegment_len = DESEGMENT_ONE_MORE_SEGMENT + pinfo.desegment_offset = offset + break end elseif (version == 0xfd) then if (buffer:len() - 2 - offset > 10) then @@ -52267,9 +52531,9 @@ function mavlink_proto.dissector(buffer,pinfo,tree) offset = offset + 3 else -- handle truncated header - local hsize = buffer:len() - 2 - offset - subtree:add(f.rawheader, buffer(offset, hsize)) - offset = offset + hsize + pinfo.desegment_len = DESEGMENT_ONE_MORE_SEGMENT + pinfo.desegment_offset = offset + break end end diff --git a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml index d059979191..44369afc76 100644 --- a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml +++ b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml @@ -6,6 +6,7 @@ icarous.xml loweheiser.xml cubepilot.xml + csAirLink.xml 2 @@ -23,10 +24,6 @@ - - - - diff --git a/ExtLibs/Mavlink/message_definitions/common.xml b/ExtLibs/Mavlink/message_definitions/common.xml index 84b29c5202..769078adbf 100644 --- a/ExtLibs/Mavlink/message_definitions/common.xml +++ b/ExtLibs/Mavlink/message_definitions/common.xml @@ -400,43 +400,49 @@ - Gimbal device (low level) capability flags (bitmap) + Gimbal device (low level) capability flags (bitmap). - Gimbal device supports a retracted position + Gimbal device supports a retracted position. - Gimbal device supports a horizontal, forward looking position, stabilized + Gimbal device supports a horizontal, forward looking position, stabilized. Gimbal device supports rotating around roll axis. - Gimbal device supports to follow a roll angle relative to the vehicle + Gimbal device supports to follow a roll angle relative to the vehicle. - Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized) + Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized). Gimbal device supports rotating around pitch axis. - Gimbal device supports to follow a pitch angle relative to the vehicle + Gimbal device supports to follow a pitch angle relative to the vehicle. - Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized) + Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized). Gimbal device supports rotating around yaw axis. - Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default) + Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). - Gimbal device supports locking to an absolute heading (often this is an option available) + Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available). Gimbal device supports yawing/panning infinetely (e.g. using slip disk). + + Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME. + + + Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation. + Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags. @@ -495,34 +501,64 @@ Set to retracted safe position (no stabilization), takes presedence over all other flags. - Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (pitch=yaw=0) but may be any orientation. + Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation. - Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal. + Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. - Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default. + Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. - Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). + Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward). + + + Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward). + + + Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North). + + + Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored). + + + The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored. + + + The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation. Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS. - Based on GIMBAL_DEVICE_FLAGS_RETRACT + Based on GIMBAL_DEVICE_FLAGS_RETRACT. - Based on GIMBAL_DEVICE_FLAGS_NEUTRAL + Based on GIMBAL_DEVICE_FLAGS_NEUTRAL. - Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK + Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK. - Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK + Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK. - Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK + Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK. + + + Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME. + + + Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. + + + Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME. + + + Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE. + + + Based on GIMBAL_DEVICE_FLAGS_RC_MIXED. @@ -543,7 +579,7 @@ There is an error with the gimbal power source. - There is an error with the gimbal motor's. + There is an error with the gimbal motors. There is an error with the gimbal's software. @@ -552,7 +588,10 @@ There is an error with the gimbal's communication. - Gimbal is currently calibrating. + Gimbal device is currently calibrating. + + + Gimbal device is not assigned to a gimbal manager. @@ -964,9 +1003,9 @@ Reach a certain target angle. - target angle, 0 is north - angular speed - direction: -1: counter clockwise, 1: clockwise + target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3. + angular speed + direction: -1: counter clockwise, 0: shortest direction, 1: clockwise 0: absolute angle, 1: relative offset Empty Empty @@ -1003,8 +1042,8 @@ Empty - Change speed and/or throttle set points. - Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed) + Change speed and/or throttle set points + Speed type of value set in param2 (such as airspeed, ground speed, and so on) Speed (-1 indicates no change, -2 indicates return to default vehicle speed) Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value) 0: absolute, 1: relative @@ -1378,7 +1417,7 @@ 0: Stop engine, 1:Start Engine 0: Warm start, 1:Cold start. Controls use of choke where applicable Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. - Empty + A bitmask of options for engine control Empty Empty Empty @@ -1612,9 +1651,7 @@ - - - High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode). Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode). Pitch rate (positive to pitch up). @@ -1623,8 +1660,6 @@ Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - - Gimbal configuration to set which sysid/compid is in primary and secondary control. Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). @@ -1633,8 +1668,21 @@ Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. - Reserved (Set to 0) + Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. + + Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. + It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). + It is also needed to specify the target camera in missions. + + When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). + If the param1 is 0 the autopilot should do both. + + When sent in a command the target MAVLink address is set using target_component. + If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). + If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. + If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. + + Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a mission Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds). Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE. Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted. @@ -1643,8 +1691,21 @@ - Stop image capture sequence Use NaN for reserved values. - Reserved (Set to 0) + Stop image capture sequence. + + Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. + It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). + It is also needed to specify the target camera in missions. + + When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). + If the param1 is 0 the autopilot should do both. + + When sent in a command the target MAVLink address is set using target_component. + If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). + If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. + If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. + + Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a mission @@ -2217,6 +2278,12 @@ Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. There is no need for the sender to retry the command, but if done during execution, the component will return MAV_RESULT_IN_PROGRESS with an updated progress. + + Command is only accepted when sent as a COMMAND_LONG. + + + Command is only accepted when sent as a COMMAND_INT. + Result of mission operation (in a MISSION_ACK message). @@ -2894,6 +2961,21 @@ The aircraft should immediately transition into guided. This should not be set for follow me applications + + Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED + + Airspeed + + + Groundspeed + + + Climb speed + + + Descent speed + + Flags in ESTIMATOR_STATUS message @@ -3304,6 +3386,12 @@ Spektrum DSMX + + Engine control options + + Allow starting the engine once while disarmed + + Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration. @@ -4545,6 +4633,17 @@ Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + + A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. + Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6 + Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. + Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. + Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset. + Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset. + Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset. + Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset. + Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset. + Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset. The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels @@ -4815,8 +4914,8 @@ Optical flow from a flow sensor (e.g. optical mouse sensor) Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. Sensor ID - Flow in x-sensor direction - Flow in y-sensor direction + Flow rate around X-axis (deprecated; use flow_rate_x) + Flow rate around Y-axis (deprecated; use flow_rate_y) Flow in x-sensor direction, angular-speed compensated Flow in y-sensor direction, angular-speed compensated Optical flow quality / confidence. 0: bad, 255: maximum quality @@ -4951,6 +5050,9 @@ True velocity in north direction in earth-fixed NED frame True velocity in east direction in earth-fixed NED frame True velocity in down direction in earth-fixed NED frame + + Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). + Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). Status generated by radio and injected into MAVLink stream. @@ -5721,6 +5823,8 @@ Bitmap of camera capability flags. Camera definition version (iteration). Use 0 if not known. Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. + + Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. @@ -5879,12 +5983,10 @@ Accuracy of heading, in NED. NAN if unknown - - Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. Timestamp (time since system boot). Bitmap of gimbal capability flags. - Gimbal device ID that this gimbal manager is responsible for. + Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) Minimum pitch angle (positive: up, negative: down) @@ -5893,17 +5995,26 @@ Maximum yaw angle (positive: to the right, negative: to the left) - - Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz). Timestamp (time since system boot). - High level gimbal manager flags currently applied. - Gimbal device ID that this gimbal manager is responsible for. + High level gimbal manager flags currently applied. + Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). System ID of MAVLink component with primary control, 0 for none. Component ID of MAVLink component with primary control, 0 for none. System ID of MAVLink component with secondary control, 0 for none. Component ID of MAVLink component with secondary control, 0 for none. + + High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + System ID + Component ID + High level gimbal manager flags to use. + Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) + X component of angular velocity, positive is rolling to the right, NaN to be ignored. + Y component of angular velocity, positive is pitching up, NaN to be ignored. + Z component of angular velocity, positive is yawing to the right, NaN to be ignored. + Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.. Timestamp (time since system boot). @@ -5915,71 +6026,85 @@ UID of gimbal hardware (0 if unknown). Bitmap of gimbal capability flags. Bitmap for use for gimbal-specific capability flags. - Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - Minimum hardware pitch angle (positive: up, negative: down) - Maximum hardware pitch angle (positive: up, negative: down) - Minimum hardware yaw angle (positive: to the right, negative: to the left) - Maximum hardware yaw angle (positive: to the right, negative: to the left) + Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. + Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. + Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. + Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. + Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. + Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. + + This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - - - Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. Angles and rates can be set to NaN according to use case. + Low level message to control a gimbal device's attitude. + This message is to be sent from the gimbal manager to the gimbal device component. + The quaternion and angular velocities can be set to NaN according to use case. + For the angles encoded in the quaternion and the angular velocities holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). + If neither of these flags are set, then (for backwards compatibility) it holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), + else they are relative to the vehicle heading (vehicle frame). + Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. + These rules are to ensure backwards compatibility. + New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. System ID Component ID Low level gimbal flags. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used) - X component of angular velocity, positive is rolling to the right, NaN to be ignored. - Y component of angular velocity, positive is pitching up, NaN to be ignored. - Z component of angular velocity, positive is yawing to the right, NaN to be ignored. + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. + X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. + Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. + Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - - - Message reporting the status of a gimbal device. This message should be broadcasted by a gimbal device component. The angles encoded in the quaternion are relative to absolute North if the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set (roll: positive is rolling to the right, pitch: positive is pitching up, yaw is turn to the right) or relative to the vehicle heading if the flag is not set. This message should be broadcast at a low regular rate (e.g. 10Hz). + Message reporting the status of a gimbal device. + This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). + For the angles encoded in the quaternion and the angular velocities holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). + If neither of these flags are set, then (for backwards compatibility) it holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), + else they are relative to the vehicle heading (vehicle frame). + Other conditions of the flags are not allowed. + The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as + q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). + If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, + then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. + New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, + and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN. System ID Component ID Timestamp (time since system boot). Current gimbal flags set. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set) - X component of angular velocity (NaN if unknown) - Y component of angular velocity (NaN if unknown) - Z component of angular velocity (NaN if unknown) - Failure flags (0 for no failure) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. + X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. + Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. + Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. + Failure flags (0 for no failure) + + Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. + Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. + This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the gimbal manager to the gimbal device component. The data of this message server for the gimbal's estimator corrections in particular horizon compensation, as well as the autopilot's control intention e.g. feed forward angular control in z-axis. + Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis. System ID Component ID Timestamp (time since system boot). Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - Estimated delay of the attitude data. - X Speed in NED (North, East, Down). - Y Speed in NED (North, East, Down). - Z Speed in NED (North, East, Down). - Estimated delay of the speed data. - Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing. + Estimated delay of the attitude data. 0 if unknown. + X Speed in NED (North, East, Down). NAN if unknown. + Y Speed in NED (North, East, Down). NAN if unknown. + Z Speed in NED (North, East, Down). NAN if unknown. + Estimated delay of the speed data. 0 if unknown. + Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. Bitmap indicating which estimator outputs are valid. The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - - - - - High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. - System ID - Component ID - High level gimbal manager flags to use. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - X component of angular velocity, positive is rolling to the right, NaN to be ignored. - Y component of angular velocity, positive is pitching up, NaN to be ignored. - Z component of angular velocity, positive is yawing to the right, NaN to be ignored. + + Z component of angular velocity in NED (North, East, Down). NaN if unknown. - - - High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. System ID Component ID High level gimbal manager flags to use. @@ -5989,6 +6114,17 @@ Pitch angular rate (positive: up, negative: down, NaN to be ignored). Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). + + High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + System ID + Component ID + High level gimbal manager flags. + Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). + Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). + Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. @@ -6195,6 +6331,12 @@ Active outputs Servo / motor output array values. Zero values indicate unused channels. + + Reports the on/off state of relays, as controlled by MAV_CMD_DO_SET_RELAY. + Timestamp (time since system boot). + Relay states. Relay instance numbers are represented as individual bits in this mask by offset. + Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured. + Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification. System ID (can be 0 for broadcast, but this is discouraged) diff --git a/ExtLibs/Mavlink/message_definitions/csAirLink.xml b/ExtLibs/Mavlink/message_definitions/csAirLink.xml new file mode 100644 index 0000000000..063d76367e --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/csAirLink.xml @@ -0,0 +1,30 @@ + + + + + + + 3 + + + + Login or password error + + + Auth successful + + + + + + Authorization package + Login + Password + + + Response to the authorization request + Response type + + + + diff --git a/ExtLibs/Mavlink/updatexmls.bat b/ExtLibs/Mavlink/updatexmls.bat index 59614334c4..bafde026ac 100644 --- a/ExtLibs/Mavlink/updatexmls.bat +++ b/ExtLibs/Mavlink/updatexmls.bat @@ -13,4 +13,6 @@ python -c "import urllib.request; print(urllib.request.urlopen('https://github.c python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/cubepilot.xml').read().decode('utf-8') )" > message_definitions\cubepilot.xml +python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/csAirLink.xml').read().decode('utf-8') )" > message_definitions\csAirLink.xml + pause \ No newline at end of file diff --git a/ExtLibs/Utilities/DFLogBuffer.cs b/ExtLibs/Utilities/DFLogBuffer.cs index 472dbaf7bd..db786a7d4d 100644 --- a/ExtLibs/Utilities/DFLogBuffer.cs +++ b/ExtLibs/Utilities/DFLogBuffer.cs @@ -8,6 +8,7 @@ using System.Text; using System.Text.RegularExpressions; using System.Threading.Tasks; +using Microsoft.CodeAnalysis.CSharp.Syntax; using Newtonsoft.Json; namespace MissionPlanner.Utilities @@ -21,36 +22,40 @@ public class DFLogBuffer : IEnumerable, IDisposable public DFLog dflog { get; } Stream basestream; - private int _count; - List linestartoffset = new List(); + private long _count; + List linestartoffset = new List(); /// /// Type and offsets /// - List[] messageindex = new List[256]; + List[] messageindex = new List[256]; /// /// Type and line numbers /// - List[] messageindexline = new List[256]; + List[] messageindexline = new List[256]; bool binary = false; object locker = new object(); - int indexcachelineno = -1; + long indexcachelineno = -1; String currentindexcache = null; public DFLogBuffer(string filename) : this(File.Open(filename,FileMode.Open,FileAccess.Read,FileShare.Read)) { + _filename = filename; } public DFLogBuffer(Stream instream) { + if (instream is FileStream) + _filename = ((FileStream)instream).Name; + dflog = new DFLog(this); for (int a = 0; a < messageindex.Length; a++) { - messageindex[a] = new List(); - messageindexline[a] = new List(); + messageindex[a] = new List(); + messageindexline[a] = new List(); } if (instream.CanSeek) @@ -90,7 +95,7 @@ void setlinecount() byte[] buffer = new byte[1024*1024]; - var lineCount = 0; + var lineCount = 0l; if (binary) { @@ -103,10 +108,10 @@ void setlinecount() continue; byte type = ans.Item1; - messageindex[type].Add((uint)(ans.Item2)); - messageindexline[type].Add((uint) lineCount); + messageindex[type].Add(ans.Item2); + messageindexline[type].Add(lineCount); - linestartoffset.Add((uint)(ans.Item2)); + linestartoffset.Add(ans.Item2); lineCount++; if (lineCount % 1000000 == 0) @@ -116,7 +121,7 @@ void setlinecount() _count = lineCount; // build fmt line database to pre seed the FMT message - messageindexline[128].ForEach(a => dflog.FMTLine(this[(int) a])); + messageindexline[128].ForEach(a => dflog.FMTLine(this[(int)a])); try { @@ -302,6 +307,89 @@ void setlinecount() indexcachelineno = -1; } + + public void SplitLog(int pieces = 0) + { + long length = basestream.Length; + + if (pieces > 0) + { + long sizeofpiece = length / pieces; + + for(int i = 0; i < pieces; i++) + { + long start = i * sizeofpiece; + long end = start + sizeofpiece; + + using (var file = File.OpenWrite(_filename + "_split" + i + ".bin")) + { + var type = dflog.logformat["FMT"]; + + var buffer = new byte[1024*256]; + + // fmt from entire file + messageindex[type.Id].ForEach(a => { + basestream.Seek(a, SeekOrigin.Begin); + int read = basestream.Read(buffer, 0, type.Length); + file.Write(buffer, 0, read); + }); + + type = dflog.logformat["FMTU"]; + + messageindex[type.Id].ForEach(a => { + basestream.Seek(a, SeekOrigin.Begin); + int read = basestream.Read(buffer, 0, type.Length); + file.Write(buffer, 0, read); + }); + + type = dflog.logformat["UNIT"]; + + messageindex[type.Id].ForEach(a => { + basestream.Seek(a, SeekOrigin.Begin); + int read = basestream.Read(buffer, 0, type.Length); + file.Write(buffer, 0, read); + }); + + type = dflog.logformat["MULT"]; + + messageindex[type.Id].ForEach(a => { + basestream.Seek(a, SeekOrigin.Begin); + int read = basestream.Read(buffer, 0, type.Length); + file.Write(buffer, 0, read); + }); + + + + var min = long.MaxValue; + var max = long.MinValue; + + // got min and max valid + linestartoffset.ForEach(a => + { + if (a >= start && a < end) + { + min = Math.Min(min, a); + max = Math.Max(max, a); + } + }); + + basestream.Seek(min, SeekOrigin.Begin); + + while (basestream.Position < max) + { + int readsize = (int)Math.Min((end - basestream.Position), buffer.Length); + int read = basestream.Read(buffer, 0, readsize); + file.Write(buffer, 0, read); + } + } + } + } + else + { + throw new Exception("Invalid pieces parameters"); + } + } + private void BuildUnitMultiList() { foreach (var msgtype in FMT) @@ -347,6 +435,7 @@ private void BuildUnitMultiList() public List> UnitMultiList = new List>(); public Dictionary value)> InstanceType = new Dictionary value)>(); + private string _filename; public Dictionary FMT { get; set; } = new Dictionary(); @@ -359,6 +448,9 @@ public DFLog.DFItem this[long indexin] { get { + if (indexin > int.MaxValue) + throw new Exception("index too large"); + var index = (int)indexin; long startoffset = linestartoffset[index]; @@ -464,7 +556,7 @@ public void Clear() public int Count { - get { return _count; } + get { if (_count > int.MaxValue) Console.WriteLine("log line count is too large"); return (int)_count; } } public bool IsReadOnly @@ -549,6 +641,8 @@ public bool IsReadOnly progress = DateTime.Now.Second; } var ans = this[(long) l]; + if (!instances.ContainsKey(ans.msgtype)) + continue; var inst = instances[ans.msgtype]; // instance was requested, and its not a match //if (inst != "" && ans.instance != inst) @@ -606,11 +700,6 @@ public List SeenMessageTypes } } - public String ReadLine() - { - return this[indexcachelineno+1]; - } - public Tuple GetUnit(string type, string header) { var answer = UnitMultiList.Where(tuple => tuple.Item1 == type && tuple.Item2 == header); diff --git a/ExtLibs/Utilities/DisplayView.cs b/ExtLibs/Utilities/DisplayView.cs index 8b935879c2..b8472ab1a1 100644 --- a/ExtLibs/Utilities/DisplayView.cs +++ b/ExtLibs/Utilities/DisplayView.cs @@ -1,4 +1,5 @@ -using System; +using org.mariuszgromada.math.mxparser.mathcollection; +using System; using System.Collections; using System.Collections.Generic; using System.IO; @@ -196,10 +197,10 @@ public DisplayView() //config tuning displayBasicTuning = true; displayExtendedTuning = true; - displayStandardParams = true; + displayStandardParams = false; displayAdvancedParams = false; - displayFullParamList = false; - displayFullParamTree = false; + displayFullParamList = true; + displayFullParamTree = true; displayParamCommitButton = false; displayBaudCMB = true; standardFlightModesOnly = false; @@ -322,10 +323,10 @@ public static DisplayView Basic(this DisplayView v) //config tuning displayBasicTuning = true, displayExtendedTuning = true, - displayStandardParams = true, + displayStandardParams = false, displayAdvancedParams = false, - displayFullParamList = false, - displayFullParamTree = false, + displayFullParamList = true, + displayFullParamTree = true, displayParamCommitButton = false, displayBaudCMB = true, displaySerialPortCMB = true, @@ -404,8 +405,8 @@ public static DisplayView Advanced(this DisplayView v) //config tuning displayBasicTuning = true, displayExtendedTuning = true, - displayStandardParams = true, - displayAdvancedParams = true, + displayStandardParams = false, + displayAdvancedParams = false, displayFullParamList = true, displayFullParamTree = true, displayParamCommitButton = false, diff --git a/ExtLibs/Utilities/Extensions.cs b/ExtLibs/Utilities/Extensions.cs index 06f5592083..897f3929d3 100644 --- a/ExtLibs/Utilities/Extensions.cs +++ b/ExtLibs/Utilities/Extensions.cs @@ -196,10 +196,33 @@ public static IEnumerable> Windowed(this IEnumerable source int index = 0; int cnt = source.Count(); - while (index < cnt) + if (source is Array) { - yield return source.Skip(index).Take(chunksize).ToArray(); - index += chunksize / divisorinc; + T[] data = (T[])source; + while (index < cnt) + { + chunksize = Math.Min(chunksize, cnt - index); + yield return new Span(data, index, chunksize).ToArray(); + index += chunksize / divisorinc; + } + } + else if (source is List) + { + List data = ((List)source); + while (index < cnt) + { + chunksize = Math.Min(chunksize, cnt - index); + yield return data.AsSpan().Slice(index, chunksize).ToArray(); + index += chunksize / divisorinc; + } + } + else + { + while (index < cnt) + { + yield return source.Skip(index).Take(chunksize).ToArray(); + index += chunksize / divisorinc; + } } } diff --git a/ExtLibs/Utilities/Spectrogram.cs b/ExtLibs/Utilities/Spectrogram.cs index c7ec415419..da48c303bf 100644 --- a/ExtLibs/Utilities/Spectrogram.cs +++ b/ExtLibs/Utilities/Spectrogram.cs @@ -23,10 +23,12 @@ public static Image GenerateImage(DFLogBuffer cb, out double[] freqtout, out List<(double timeus, double[] value)> allfftdata, string type = "ACC1", string field = "AccX", string timeus = "TimeUS", int min = -80, int max = -20) { + Console.WriteLine("GenerateImage " + type + " " + field); allfftdata = new List<(double timeus, double[] value)>(); if (cb.SeenMessageTypes.Contains("ISBH")) { + Console.WriteLine("GenerateImage seen ISBH"); int sensorno = (type.Contains("1") ? 0 : (type.Contains("2") ? 1 : 2)); int sensor = type.Contains("ACC") ? 0 : 1; int Ns = -1; @@ -117,6 +119,8 @@ public static Image GenerateImage(DFLogBuffer cb, out double[] freqtout, int done = 0; // 50% overlap int divisor = 4; + if (count > 2048) + divisor = 1; count *= divisor; var img = new Image(count, freqt.Length); log.Debug("done and count "); @@ -183,7 +187,10 @@ public static Image GenerateImage(DFLogBuffer cb, out double[] freqtout, double timedelta = 0; // 50% overlap int divisor = 4; + if (count > 2048) + divisor = 1; count *= divisor; + Console.WriteLine("Image Size " + count + " " + N / 2); var img = new Image(count, N / 2); log.Debug("done and count "); diff --git a/ExtLibs/Utilities/ZeroConf.cs b/ExtLibs/Utilities/ZeroConf.cs index 1758d76c6f..ec4d0d75ab 100644 --- a/ExtLibs/Utilities/ZeroConf.cs +++ b/ExtLibs/Utilities/ZeroConf.cs @@ -18,8 +18,7 @@ public class ZeroConf public static void ProbeForRTSP() { - if(!System.Diagnostics.Debugger.IsAttached) - resolverAsync(); + resolverAsync(); } private static async Task resolverAsync() @@ -60,8 +59,7 @@ public static async Task EnumerateAllServicesFromAllHosts() public static void ProbeForMavlink() { - if (!System.Diagnostics.Debugger.IsAttached) - resolverMavlinkAsync(); + resolverMavlinkAsync(); } private static async Task resolverMavlinkAsync() diff --git a/ExtLibs/Xamarin/Xamarin.Android/MainActivity.cs b/ExtLibs/Xamarin/Xamarin.Android/MainActivity.cs index 612eff086f..f0bf1ae3bb 100644 --- a/ExtLibs/Xamarin/Xamarin.Android/MainActivity.cs +++ b/ExtLibs/Xamarin/Xamarin.Android/MainActivity.cs @@ -89,13 +89,13 @@ namespace Xamarin.Droid { //global::Android.Content.Intent.CategoryLauncher //global::Android.Content.Intent.CategoryHome, [IntentFilter(new[] { global::Android.Content.Intent.ActionMain, global::Android.Content.Intent.ActionAirplaneModeChanged , - global::Android.Content.Intent.ActionBootCompleted , UsbManager.ActionUsbDeviceAttached, UsbManager.ActionUsbDeviceDetached, - global::Android.Bluetooth.BluetoothDevice.ActionFound, global::Android.Bluetooth.BluetoothDevice.ActionAclConnected, UsbManager.ActionUsbAccessoryAttached}, - Categories = new []{ global::Android.Content.Intent.CategoryLauncher})] + global::Android.Content.Intent.ActionBootCompleted , UsbManager.ActionUsbDeviceAttached, UsbManager.ActionUsbDeviceDetached, + global::Android.Bluetooth.BluetoothDevice.ActionFound, global::Android.Bluetooth.BluetoothDevice.ActionAclConnected, UsbManager.ActionUsbAccessoryAttached}, + Categories = new[] { global::Android.Content.Intent.CategoryLauncher })] [IntentFilter(actions: new[] { global::Android.Content.Intent.ActionView }, Categories = new[] { global::Android.Content.Intent.CategoryBrowsable, global::Android.Content.Intent.ActionDefault, global::Android.Content.Intent.CategoryOpenable }, DataHost = "*", DataPathPattern = ".*\\.tlog", DataMimeType = "*/*", DataSchemes = new[] { "file", "http", "https", "content" })] - [IntentFilter(actions: new[] { global::Android.Content.Intent.ActionView }, Categories = new[] { global::Android.Content.Intent.CategoryBrowsable, global::Android.Content.Intent.ActionDefault, global::Android.Content.Intent.CategoryOpenable }, DataHost = "*", DataPathPattern = ".*\\.bin", DataMimeType = "*/*", DataSchemes = new[] { "file", "http", "https", "content" })] + [IntentFilter(actions: new[] { global::Android.Content.Intent.ActionView }, Categories = new[] { global::Android.Content.Intent.CategoryBrowsable, global::Android.Content.Intent.ActionDefault, global::Android.Content.Intent.CategoryOpenable }, DataHost = "*", DataPathPattern = ".*\\.bin", DataMimeType = "*/*", DataSchemes = new[] { "file", "http", "https", "content" })] [MetaData("android.hardware.usb.action.USB_DEVICE_ATTACHED", Resource = "@xml/device_filter")] - [Activity(Label = "Mission Planner", Exported = true, ScreenOrientation = ScreenOrientation.SensorLandscape, Icon = "@mipmap/icon", Theme = "@style/MainTheme", + [Activity(Label = "Mission Planner", Exported = true, ScreenOrientation = ScreenOrientation.SensorLandscape, Icon = "@mipmap/icon", Theme = "@style/MainTheme", MainLauncher = true, HardwareAccelerated = true, DirectBootAware = true, Immersive = true, LaunchMode = LaunchMode.SingleInstance)] public class MainActivity : global::Xamarin.Forms.Platform.Android.FormsAppCompatActivity { @@ -141,7 +141,7 @@ protected override void OnActivityResult(int requestCode, Result resultCode, Int var query = this.ContentResolver.Query(docUriTree, null, null, null, null); query.MoveToFirst(); - var filePath = query.GetString(0); + var filePath = query.GetString(0); query.Close(); pref.Edit().PutString("Directory", filePath).Commit(); @@ -173,7 +173,7 @@ protected override void OnCreate(Bundle savedInstanceState) TabLayoutResource = Resource.Layout.Tabbar; ToolbarResource = Resource.Layout.Toolbar; - SetSupportActionBar((Toolbar) FindViewById(ToolbarResource)); + SetSupportActionBar((Toolbar)FindViewById(ToolbarResource)); this.Window.AddFlags(WindowManagerFlags.Fullscreen | WindowManagerFlags.TurnScreenOn | WindowManagerFlags.HardwareAccelerated); @@ -304,11 +304,11 @@ void ContinueInit() { if (ContextCompat.CheckSelfPermission(this, Manifest.Permission.AccessFineLocation) != - (int) Permission.Granted || + (int)Permission.Granted || ContextCompat.CheckSelfPermission(this, Manifest.Permission.WriteExternalStorage) != - (int) Permission.Granted || + (int)Permission.Granted || ContextCompat.CheckSelfPermission(this, Manifest.Permission.Bluetooth) != - (int) Permission.Granted) + (int)Permission.Granted) { ActivityCompat.RequestPermissions(this, new String[] @@ -318,15 +318,7 @@ void ContinueInit() Manifest.Permission.Bluetooth }, 1); } - - while (ContextCompat.CheckSelfPermission(this, Manifest.Permission.WriteExternalStorage) != - (int) Permission.Granted) - { - Thread.Sleep(1000); - var text = "Checking Permissions - " + DateTime.Now.ToString("T"); - - //DoToastMessage(text); - } + } try { diff --git a/ExtLibs/px4uploader/Firmware.cs b/ExtLibs/px4uploader/Firmware.cs index c7e77983f5..975abb6484 100644 --- a/ExtLibs/px4uploader/Firmware.cs +++ b/ExtLibs/px4uploader/Firmware.cs @@ -178,12 +178,8 @@ public int crc(int padlen) public int extf_crc(int padlen) { - uint state = __crc32(extf_imagebyte, 0); + uint state = __crc32(extf_imagebyte.Take(padlen).ToArray(), 0); - for (int i = extf_imagebyte.Length; i < (padlen - 1); i += 4) - { - state = __crc32(crcpad, state); - } return (int)state; } } diff --git a/ExtLibs/wasm/Pages/Websocket.razor b/ExtLibs/wasm/Pages/Websocket.razor index d0b1160f99..9d333ae878 100644 --- a/ExtLibs/wasm/Pages/Websocket.razor +++ b/ExtLibs/wasm/Pages/Websocket.razor @@ -87,6 +87,7 @@ Raw MAVLink website url (wss:// for https)

+ @@ -120,7 +121,7 @@ } } - + @functions { @@ -184,6 +185,7 @@ string wsuri { get; set; } = "ws://localhost:56781/websocket/raw"; bool pageloadvisible = true; + static Websocket Instance; private void Log(string message) => Console.WriteLine($"{DateTime.UtcNow.ToString("O")} - {message}"); @@ -194,6 +196,8 @@ init = false; + Instance = this; + Console.WriteLine("OnInitialized Done"); } @@ -201,11 +205,42 @@ //protected WebSocketHelper WebSocketHelper1; + public async Task serialconnect() + { + pageloadvisible = false; + running = false; + StateHasChanged(); + + await JSRuntime.InvokeAsync("evalline", new object[] { @" +serial.requestPort() + .then(port => { + port.connect().then(()=>{ + console.log('connected'); + window.serialport = port; + port.onReceive = (data) => { DotNet.invokeMethodAsync('wasm', 'ProcessPacketStatic', '', data);} + }); + }); +" }).ConfigureAwait(false); + + mavbasestream.ReadBufferUpdate += (sender, i) => { }; + mavbasestream.WriteCallback += async (sender, bytes) => + { + if (bytes.Count() == 0) + return; + await JS.InvokeAsync("window.serialport.send", bytes.ToArray()); + }; + + + JSRuntime.InvokeAsync("startChart"); + + StateHasChanged(); + } + public async Task wsconnect() { - - ClientWebSocket webSocket = new ClientWebSocket(); - Console.WriteLine(wsuri); + + ClientWebSocket webSocket = new ClientWebSocket(); + Console.WriteLine(wsuri); await webSocket.ConnectAsync(new Uri(wsuri), CancellationToken.None).ContinueWith(async (a) => { pageloadvisible = false; @@ -213,22 +248,22 @@ ArraySegment bytesReceived = new ArraySegment (new byte[1024]); - Toaster.Info(webSocket.State.ToString()); + Toaster.Info(webSocket.State.ToString()); while (webSocket.State == WebSocketState.Open) { //Console.WriteLine("webSocket.ReceiveAsync"); await webSocket.ReceiveAsync(bytesReceived, CancellationToken.None); - ProcessPacket("", bytesReceived.Array.ToArray()); + this.ProcessPacket("", bytesReceived.Array.ToArray()); } }); - mavbasestream.ReadBufferUpdate += (sender, i) => { }; - mavbasestream.WriteCallback += async (sender, bytes) => { await webSocket.SendAsync(new ArraySegment - (bytes.ToArray()), WebSocketMessageType.Binary, true, CancellationToken.None); }; + mavbasestream.ReadBufferUpdate += (sender, i) => { }; + mavbasestream.WriteCallback += async (sender, bytes) => { await webSocket.SendAsync(new ArraySegment + (bytes.ToArray()), WebSocketMessageType.Binary, true, CancellationToken.None); }; + - //JSRuntime.InvokeAsync("initWebSocket", wsuri); JSRuntime.InvokeAsync("startChart"); @@ -239,30 +274,30 @@ /* private void WsOnError(string obj) { - SpeechSynthesis.Speak(obj); - Toaster.Error(obj); - StateHasChanged(); + SpeechSynthesis.Speak(obj); + Toaster.Error(obj); + StateHasChanged(); } private void WsOnMessage(BwsMessage obj) { - ProcessPacket("", obj.MessageBinary); + ProcessPacket("", obj.MessageBinary); } private void WsOnStateChange(short obj) { - if (WebSocketHelper1.bwsState == BwsState.Open) - { - pageloadvisible = false; - } - else + if (WebSocketHelper1.bwsState == BwsState.Open) + { + pageloadvisible = false; + } + else { - pageloadvisible = true; - } - SpeechSynthesis.Speak(WebSocketHelper1.bwsState.ToString()); - Toaster.Info(WebSocketHelper1.bwsState.ToString()); - StateHasChanged(); + pageloadvisible = true; + } + SpeechSynthesis.Speak(WebSocketHelper1.bwsState.ToString()); + Toaster.Info(WebSocketHelper1.bwsState.ToString()); + StateHasChanged(); } */ @@ -270,12 +305,10 @@ protected override async Task OnAfterRenderAsync(bool firstRender) { - Log("OnAfterRenderAsync"); - if (init) return; - + Log("OnAfterRenderAsync"); init = true; @@ -297,6 +330,7 @@ _hud.Height = (int)_canvasReference.Height; } } + protected BECanvasComponent _canvasReference; protected override void OnParametersSet() @@ -314,9 +348,13 @@ } + [JSInvokable] + public static async void ProcessPacketStatic(string json, byte[] data = null) + { + Instance.ProcessPacket(json, data); + } - //[JSInvokable] public async void ProcessPacket(string json, byte[] data = null) { //Console.WriteLine(DateTime.Now + " JS to C# " + json.ToArray().Length); @@ -363,7 +401,7 @@ mavbasestream.AppendBuffer(data); - /* + /* var pos = mav.logplaybackfile.BaseStream.Position; mav.logplaybackfile.BaseStream.Seek(0, SeekOrigin.End); @@ -379,7 +417,7 @@ mav.logplaybackfile.BaseStream.Seek(pos, SeekOrigin.Begin); mav.logreadmode = true; - */ + */ //Console.WriteLine("open {0} btr {1} type {2} type {3}", mav.BaseStream.IsOpen, mav.BaseStream.BytesToRead, mav.BaseStream.GetType(), mav.BaseStream.BaseStream?.GetType()); var check1 = DateTime.Now; @@ -575,8 +613,11 @@ // once a second if (second != DateTime.Now.Second) { - second = DateTime.Now.Second; - StateHasChanged(); + if (mode == modes.map) + { + second = DateTime.Now.Second; + StateHasChanged(); + } } return true; diff --git a/ExtLibs/wasm/wasm.csproj b/ExtLibs/wasm/wasm.csproj index b66f407076..cb8f325ffa 100644 --- a/ExtLibs/wasm/wasm.csproj +++ b/ExtLibs/wasm/wasm.csproj @@ -1,15 +1,16 @@  - net7.0 - + net8.0 + 3.0 false true true - - false + true + false + false @@ -36,26 +37,25 @@ - + - - - - - + + + + - + - - - + + + - + diff --git a/ExtLibs/wasm/wwwroot/console.js b/ExtLibs/wasm/wwwroot/console.js index 943aeb17ee..98592fcc7d 100644 --- a/ExtLibs/wasm/wwwroot/console.js +++ b/ExtLibs/wasm/wwwroot/console.js @@ -73,13 +73,5 @@ } }); - serial.getPorts().then(ports => { - if (ports.length == 0) { - t.io.println('No devices found.'); - } else { - port = ports[0]; - connect(); - } - }); }); })(); \ No newline at end of file diff --git a/ExtLibs/wasm/wwwroot/serial.js b/ExtLibs/wasm/wwwroot/serial.js index 2efc47bb44..6fd121892a 100644 --- a/ExtLibs/wasm/wwwroot/serial.js +++ b/ExtLibs/wasm/wwwroot/serial.js @@ -1,101 +1,127 @@ var serial = {}; -(function() { - 'use strict'; +(function () { + 'use strict'; - serial.getPorts = function() { - return navigator.usb.getDevices().then(devices => { - return devices.map(device => new serial.Port(device)); - }); - }; - - serial.requestPort = function() { - const filters = [ - /* { 'vendorId': 0x2341, 'productId': 0x8036 }, // Arduino Leonardo - { 'vendorId': 0x2341, 'productId': 0x8037 }, // Arduino Micro - { 'vendorId': 0x2341, 'productId': 0x804d }, // Arduino/Genuino Zero - { 'vendorId': 0x2341, 'productId': 0x804e }, // Arduino/Genuino MKR1000 - { 'vendorId': 0x2341, 'productId': 0x804f }, // Arduino MKRZERO - { 'vendorId': 0x2341, 'productId': 0x8050 }, // Arduino MKR FOX 1200 - { 'vendorId': 0x2341, 'productId': 0x8052 }, // Arduino MKR GSM 1400 - { 'vendorId': 0x2341, 'productId': 0x8053 }, // Arduino MKR WAN 1300 - { 'vendorId': 0x2341, 'productId': 0x8054 }, // Arduino MKR WiFi 1010 - { 'vendorId': 0x2341, 'productId': 0x8055 }, // Arduino MKR NB 1500 - { 'vendorId': 0x2341, 'productId': 0x8056 }, // Arduino MKR Vidor 4000 - { 'vendorId': 0x2341, 'productId': 0x8057 }, // Arduino NANO 33 IoT - { 'vendorId': 0x239A }, // Adafruit Boards!*/ - { 'vendorId': 0x2dae }, // Hex Boards! - ]; - return navigator.usb.requestDevice({ 'filters': filters }).then( - device => new serial.Port(device) - ); - } + serial.getPorts = function () { + return navigator.usb.getDevices().then(devices => { + return devices.map(device => new serial.Port(device)); + }); + }; - serial.Port = function(device) { - this.device_ = device; - this.interfaceNumber_ = 2; // original interface number of WebUSB Arduino demo - this.endpointIn_ = 5; // original in endpoint ID of WebUSB Arduino demo - this.endpointOut_ = 4; // original out endpoint ID of WebUSB Arduino demo - }; + serial.requestPort = function () { + const filters = [ + /* { 'vendorId': 0x2341, 'productId': 0x8036 }, // Arduino Leonardo + { 'vendorId': 0x2341, 'productId': 0x8037 }, // Arduino Micro + { 'vendorId': 0x2341, 'productId': 0x804d }, // Arduino/Genuino Zero + { 'vendorId': 0x2341, 'productId': 0x804e }, // Arduino/Genuino MKR1000 + { 'vendorId': 0x2341, 'productId': 0x804f }, // Arduino MKRZERO + { 'vendorId': 0x2341, 'productId': 0x8050 }, // Arduino MKR FOX 1200 + { 'vendorId': 0x2341, 'productId': 0x8052 }, // Arduino MKR GSM 1400 + { 'vendorId': 0x2341, 'productId': 0x8053 }, // Arduino MKR WAN 1300 + { 'vendorId': 0x2341, 'productId': 0x8054 }, // Arduino MKR WiFi 1010 + { 'vendorId': 0x2341, 'productId': 0x8055 }, // Arduino MKR NB 1500 + { 'vendorId': 0x2341, 'productId': 0x8056 }, // Arduino MKR Vidor 4000 + { 'vendorId': 0x2341, 'productId': 0x8057 }, // Arduino NANO 33 IoT + { 'vendorId': 0x239A }, // Adafruit Boards!*/ + { 'vendorId': 0x2dae }, // Hex Boards! + ]; + return navigator.serial.requestPort({ 'filter': filters }).then( + device => new serial.Port(device) + ); + /* + await comm.open({ baudRate: 115200, bufferSize: 64 }); + reader = comm.readable.getReader(); + writer = comm.writable.getWriter(); + return navigator.usb.requestDevice({ 'filters': filters }).then( + device => new serial.Port(device) + );*/ + } - serial.Port.prototype.connect = function() { - let readLoop = () => { - this.device_.transferIn(this.endpointIn_, 64).then(result => { - this.onReceive(result.data); - readLoop(); - }, error => { - this.onReceiveError(error); - }); + serial.Port = function (device) { + this.device_ = device; + this.run = false; + //this.interfaceNumber_ = 1; // original interface number of WebUSB Arduino demo + //this.endpointIn_ = 2; // original in endpoint ID of WebUSB Arduino demo + //this.endpointOut_ = 2; // original out endpoint ID of WebUSB Arduino demo }; - return this.device_.open() - .then(() => { - if (this.device_.configuration === null) { - return this.device_.selectConfiguration(1); - } - }) - .then(() => { - var configurationInterfaces = this.device_.configuration.interfaces; - configurationInterfaces.forEach(element => { - element.alternates.forEach(elementalt => { - if (elementalt.interfaceClass==0xff) { - this.interfaceNumber_ = element.interfaceNumber; - elementalt.endpoints.forEach(elementendpoint => { - if (elementendpoint.direction == "out") { - this.endpointOut_ = elementendpoint.endpointNumber; - } - if (elementendpoint.direction=="in") { - this.endpointIn_ =elementendpoint.endpointNumber; + serial.Port.prototype.connect = function () { + return this.device_.open({ baudRate: 115200 }).then(() => { + this.run = true; + this.reader = this.device_.readable.getReader(); + this.writer = this.device_.writable.getWriter(); + + let readLoop = () => { + this.reader.read().then(result => { + this.onReceive(result.value); + if (this.run) + setTimeout(readLoop, 10); + }); + /*this.device_.transferIn(this.endpointIn_, 64).then(result => { + this.onReceive(result.data); + readLoop(); + }, error => { + this.onReceiveError(error); + });*/ + }; + + setTimeout(readLoop, 10); + }); + /* + return this.device_.open() + .then(() => { + if (this.device_.configuration === null) { + return this.device_.selectConfiguration(1); + } + }) + .then(() => { + var configurationInterfaces = this.device_.configuration.interfaces; + configurationInterfaces.forEach(element => { + element.alternates.forEach(elementalt => { + if (elementalt.interfaceClass==0xff) { + this.interfaceNumber_ = element.interfaceNumber; + elementalt.endpoints.forEach(elementendpoint => { + if (elementendpoint.direction == "out") { + this.endpointOut_ = elementendpoint.endpointNumber; + } + if (elementendpoint.direction=="in") { + this.endpointIn_ =elementendpoint.endpointNumber; + } + }) } }) - } + }) }) - }) - }) - .then(() => this.device_.claimInterface(this.interfaceNumber_)) - .then(() => this.device_.selectAlternateInterface(this.interfaceNumber_, 0)) - .then(() => this.device_.controlTransferOut({ - 'requestType': 'class', - 'recipient': 'interface', - 'request': 0x22, - 'value': 0x01, - 'index': this.interfaceNumber_})) - .then(() => { - readLoop(); - }); - }; + .then(() => this.device_.claimInterface(this.interfaceNumber_)) + .then(() => this.device_.selectAlternateInterface(this.interfaceNumber_, 0)) + .then(() => this.device_.controlTransferOut({ + 'requestType': 'class', + 'recipient': 'interface', + 'request': 0x22, + 'value': 0x01, + 'index': this.interfaceNumber_})) + .then(() => { + readLoop(); + });*/ + }; - serial.Port.prototype.disconnect = function() { - return this.device_.controlTransferOut({ + serial.Port.prototype.disconnect = function () { + /*return this.device_.controlTransferOut({ 'requestType': 'class', 'recipient': 'interface', 'request': 0x22, 'value': 0x00, - 'index': this.interfaceNumber_}) - .then(() => this.device_.close()); - }; + 'index': this.interfaceNumber_ + }) + .then(() => this.device_.close()); + */ + this.run = false; + return this.device_.close(); + }; - serial.Port.prototype.send = function(data) { - return this.device_.transferOut(this.endpointOut_, data); - }; + serial.Port.prototype.send = function (data) { + return this.writer.write(data); + //return this.device_.transferOut(this.endpointOut_, data); + }; })(); diff --git a/GCSViews/ConfigurationView/ConfigPlanner.cs b/GCSViews/ConfigurationView/ConfigPlanner.cs index 5e7fd49b75..4c11bd9ed2 100644 --- a/GCSViews/ConfigurationView/ConfigPlanner.cs +++ b/GCSViews/ConfigurationView/ConfigPlanner.cs @@ -720,6 +720,10 @@ private void CHK_maprotation_CheckedChanged(object sender, EventArgs e) if (startup) return; Settings.Instance["CHK_maprotation"] = CHK_maprotation.Checked.ToString(); + if (CHK_maprotation.Checked) + { + chk_shownofly.Checked = false; + } FlightData.instance.gMapControl1.Bearing = 0; } @@ -987,6 +991,10 @@ private void CHK_AutoParamCommit_CheckedChanged(object sender, EventArgs e) private void chk_shownofly_CheckedChanged(object sender, EventArgs e) { Settings.Instance["ShowNoFly"] = chk_shownofly.Checked.ToString(); + if (chk_shownofly.Checked) + { + CHK_maprotation.Checked = false; + } } private void CMB_altunits_SelectedIndexChanged(object sender, EventArgs e) diff --git a/GCSViews/ConfigurationView/ConfigPlanner.ko-KR.resx b/GCSViews/ConfigurationView/ConfigPlanner.ko-KR.resx index 219966a6e0..6f664d8bd1 100644 --- a/GCSViews/ConfigurationView/ConfigPlanner.ko-KR.resx +++ b/GCSViews/ConfigurationView/ConfigPlanner.ko-KR.resx @@ -117,2303 +117,501 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl - - 496, 227 - - - 43, 13 - - - - 87 + 496, 256 센서 - - label33 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 31 - - - -1 - - - 0 - - - 1 - - - 2 - - - 3 - - - 4 - - - 5 - - - 6 - - - 7 - - - 8 - - - 9 - - - 10 - - - 25 - - - 50 - - - 100 - - 545, 224 - - - 40, 21 - - - 88 - - - CMB_ratesensors - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 32 - - - True - - - NoControl - - - 9, 38 + 545, 253 - 69, 13 - - - 86 + 54, 16 영상 형식 - - label26 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 33 - - - 107, 35 - - - 408, 21 - - - 44 - - - CMB_videoresolutions - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 34 - - - True - - - NoControl - - 9, 323 + 9, 352 - 31, 13 - - - 84 + 92, 16 투영 영상(HUD) - - label12 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 35 - - - NoControl - - 107, 322 - - - 220, 17 - - - 85 + 107, 351 GDI+ (구형/하드웨어 가속 아님) - - CHK_GDIPlus - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 36 - - - True - - - NoControl - - 9, 300 + 9, 329 - 57, 13 - - - 82 + 54, 16 경로 지점 - - label24 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 37 - - - NoControl - - 107, 299 - - - 177, 17 - - - 83 + 107, 328 연결시 경로 불러오기 - - CHK_loadwponconnect - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 38 - - - True - - - NoControl - - 9, 274 + 9, 303 - 71, 13 - - - 81 + 54, 16 트랙 길이 - - label23 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 39 - - 107, 273 - - - 67, 20 - - - 80 - - - NUM_tracklength - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 40 - - - True - - - NoControl + 107, 302 - 515, 89 + 592, 90 - 81, 17 - - - 79 + 73, 20 고도 경고 - - False - - - CHK_speechaltwarning - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 41 - - - True - - - NoControl - - 9, 251 + 9, 280 - 78, 13 - - - 45 + 65, 16 연결 재설정 - - label108 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 42 - - - NoControl - - 107, 250 - - - 217, 17 - - - 46 + 107, 279 USB 연결시 초기화(DTR 전환) - - CHK_resetapmonconnect - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 43 - - - Bottom, Left - - - NoControl - - 107, 550 + 107, 609 144, 17 - - 47 - MAVLink 메세지 디버깅 - - CHK_mavdebug - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 44 - - - NoControl - - 422, 227 - - - 22, 13 - - - 48 + 422, 256 원격 조종기 - - label107 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 45 - - - -1 - - - 0 - - - 1 - - - 2 - - - 3 - - - 4 - - - 5 - - - 6 - - - 7 - - - 8 - - - 9 - - - 10 - - - 25 - - - 35 - - - 50 - - 450, 224 - - - 40, 21 - - - 49 - - - CMB_raterc - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 46 - - - NoControl + 450, 253 - 301, 227 + 301, 256 69, 13 - - 50 - 모드/상태 - - label104 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 47 - - - NoControl - - 205, 227 + 205, 256 44, 13 - - 51 - 위치 - - label103 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 48 - - - NoControl - - 104, 227 + 104, 256 43, 13 - - 52 - 고도 - - label102 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 49 - - - True - - - NoControl - - 9, 227 + 9, 256 - 84, 13 - - - 53 + 79, 16 원격 측정 속도 - - label101 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 50 - - - -1 - - - 0 - - - 1 - - - 2 - - - 3 - - - 4 - - - 5 - - - 6 - - - 7 - - - 8 - - - 9 - - - 10 - - - 25 - - - 35 - - - 50 - - 376, 224 - - - 40, 21 - - - 54 - - - CMB_ratestatus - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 51 - - - -1 - - - 0 - - - 1 - - - 2 - - - 3 - - - 4 - - - 5 - - - 6 - - - 7 - - - 8 - - - 9 - - - 10 - - - 20 - - - 50 - - - 100 + 376, 253 - 255, 224 - - - 40, 21 - - - 55 - - - CMB_rateposition - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 52 - - - -1 - - - 0 - - - 1 - - - 2 - - - 3 - - - 4 - - - 5 - - - 6 - - - 7 - - - 8 - - - 9 - - - 10 - - - 50 - - - 100 + 255, 253 - 153, 224 - - - 40, 21 - - - 56 - - - CMB_rateattitude - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 53 - - - NoControl + 153, 253 - 480, 171 - - - 241, 31 - - - 57 + 480, 200 참고: 설정 탭에서는 원시 값을 보여주므로 단위를 표시하지 않음. - - label99 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 54 - - - True - - - NoControl - - 9, 198 + 9, 227 - 65, 13 - - - 58 + 54, 16 속력 단위 - - label98 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 55 - - - True - - - NoControl - - 9, 171 + 9, 200 - 52, 13 - - - 59 + 54, 16 거리 단위 - - label97 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 56 - - 107, 195 - - - 138, 21 - - - 60 - - - CMB_speedunits - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 57 + 107, 224 - 107, 168 - - - 138, 21 - - - 61 - - - CMB_distunits - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 58 - - - True - - - NoControl + 107, 197 - 9, 144 + 9, 173 - 45, 13 - - - 62 + 51, 16 조이스틱 - - label96 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 59 - - - True - - - NoControl - - - 9, 90 - - - 44, 13 - - - 63 - 음성 안내 - - label95 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 60 - - - True - - - NoControl - - 412, 89 + 489, 90 - 102, 17 - - - 64 + 84, 20 배터리 경고 - - False - - - CHK_speechbattery - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 61 - - - True - - - NoControl - - 332, 89 + 409, 90 - 81, 17 - - - 65 + 76, 20 30초 간격 - - False - - - CHK_speechcustom - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 62 - - - True - - - NoControl - - 280, 89 + 343, 89 - 56, 17 - - - 66 + 51, 20 모드 - - False - - - CHK_speechmode - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 63 - - - True - - - NoControl - 207, 89 - - 71, 17 - - - 67 - - - 경로 지점 - - - False - - - CHK_speechwaypoint - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 64 - - - True - - - NoControl - - - 9, 65 - - - 57, 13 - - - 68 - - - OSD 색상 - - - label94 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 65 - - - 107, 62 - - - 138, 21 - - - 69 - - - CMB_osdcolor - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 66 - - - 107, 112 - - - 138, 21 - - - 70 - - - CMB_language - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 67 - - - True - - - NoControl - - - 9, 115 - - - 69, 13 - - - 71 - - - 인터페이스 언어 - - - label93 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 68 - - - True - - - NoControl - - - 107, 89 - - - 99, 17 - - - 72 - - - 음성 안내 활성 - - - CHK_enablespeech - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 69 - - - NoControl - - - 520, 10 - - - 125, 17 - - - 73 - - - 투영 영상(HUD) 오버레이 - - - CHK_hudshow - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 70 - - - True - - - NoControl - - - 9, 11 - - - 71, 13 - - - 74 - - - 영상 장치 - - - label92 + + 73, 20 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 경로 지점 - - $this + + 61, 16 - - 71 + + OSD 색상 - - 107, 8 + + 107, 108 - - 245, 21 + + 107, 138 - - 75 + + 9, 141 - - CMB_videosources + + 87, 16 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 인터페이스 언어 - - $this + + 98, 20 - - 72 + + 음성 안내 활성 - - True + + 125, 17 - - NoControl + + 투영 영상(HUD) 오버레이 - - 9, 346 + + 54, 16 - - 61, 13 + + 영상 장치 - - 89 + + 9, 375 지도 따라가기 - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 29 - - - NoControl - - 107, 345 - - - 205, 17 - - - 90 + 107, 374 비행체 방향 따라 지도 회전 - - CHK_maprotation - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 30 - - - NoControl - - 338, 274 - - - 81, 17 - - - 91 + 338, 303 원점 거리 - - label2 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 27 - - - NoControl - - 430, 273 - - - 129, 17 - - - 92 + 430, 302 비행 데이터 표시 - - CHK_disttohomeflightdata - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 28 - - - NoControl - - 107, 139 - - - 99, 23 - - - 76 + 107, 168 조이스틱 설정 - - BUT_Joystick - - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 73 - - - NoControl - - - 439, 6 - - - 75, 23 - - - 77 - 정지 - - BUT_videostop - - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 74 - - - NoControl - - - 358, 6 - - - 75, 23 - - - 78 - 시작 - - BUT_videostart - - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 75 - - - True - - - NoControl - - 9, 371 + 9, 400 - 50, 13 - - - 93 + 79, 16 로그 저장 경로 - - label3 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 26 - - 107, 368 - - - 386, 20 - - - 94 - - - txt_log_dir - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 25 - - - NoControl + 107, 397 - 496, 366 - - - 75, 23 - - - 95 + 496, 395 탐색 - - BUT_logdirbrowse - - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 24 - - - True - - - NoControl - - 9, 397 + 9, 426 - 40, 13 - - - 96 + 29, 16 테마 - - label4 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 23 - - 107, 394 - - - 138, 21 - - - 97 - - - CMB_theme - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 22 - - - NoControl + 107, 423 - 249, 394 - - - 75, 20 - - - 98 + 249, 423 개별 설정 - - BUT_themecustom - - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 21 - - - True - - - NoControl - - 594, 89 + 671, 90 - 81, 17 - - - 99 + 74, 20 시동/제동 - - False - - - CHK_speecharmdisarm - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 20 - - - NoControl - - 107, 474 - - - 99, 20 - - - 100 + 107, 503 승강계 켬/끔 - - BUT_Vario - - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - - $this - - - 19 - - - True - - - NoControl - - 107, 500 + 107, 529 - 115, 17 - - - 102 + 98, 20 익명 상황 제외 - - chk_analytics - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 18 - - - True - - - NoControl - - 228, 500 + 228, 529 - 91, 17 - - - 103 + 95, 20 베타 업데이트 - - CHK_beta - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 17 - - - True - - - NoControl - - 340, 477 + 340, 506 - 142, 17 - - - 104 + 98, 20 암호 보호 설정 - - CHK_Password - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 16 - - - True - - - NoControl - - 671, 89 + 748, 90 - 80, 17 - - - 105 + 48, 20 저속 - - False - - - CHK_speechlowspeed - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 15 - - - True - - - NoControl - - 496, 477 + 496, 506 - 91, 17 - - - 107 + 73, 20 공항 표시 - - CHK_showairports - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 14 - - - True - - - NoControl - - 598, 477 - - - 55, 17 - - - 108 - - - ADSB - - - chk_ADSB - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 13 - - - True - - - NoControl + 598, 506 - 496, 500 + 496, 529 - 54, 17 - - - 109 + 73, 20 고도 유지 - - chk_tfr - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 12 - - - Bottom, Left - - - NoControl - - 341, 550 - - - 144, 17 - - - 110 + 341, 609 시험 화면 - - chk_temp - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 11 - - - True - - - NoControl - - 340, 500 + 340, 529 - 104, 17 - - - 111 + 131, 20 원격조종 수신기 없음 - - chk_norcreceiver - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - 107, 421 - - - 138, 21 - - - 113 - - - CMB_Layout - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 8 - - - True - - - NoControl + 107, 450 - 9, 424 + 9, 453 - 39, 13 - - - 115 + 29, 16 배치 - - label5 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - True - - 598, 501 + 598, 530 - 123, 17 - - - 116 + 120, 20 매개변수 자동 반영 - - CHK_AutoParamCommit - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 6 - - - True - - - NoControl - - 671, 477 + 671, 506 - 56, 17 - - - 117 + 73, 20 비행 안함 - - chk_shownofly - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - True - - - NoControl - - 249, 171 + 249, 200 - 46, 13 - - - 118 + 54, 16 고도 단위 - - label6 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - - 320, 168 - - - 138, 21 - - - 119 - - - CMB_altunits - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 4 + 320, 197 - 107, 448 - - - 53, 20 - - - 120 - - - num_gcsid - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 2 - - - True - - - NoControl + 107, 477 - 9, 450 + 9, 479 - 43, 13 - - - 121 + 70, 16 지상 통제 ID - - label7 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 1 - - - True - - - NoControl - - 107, 523 + 107, 552 - 186, 17 - - - 122 + 197, 20 백그라운드에서 매개변수 다운로드 - - CHK_params_bg - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 341, 555 - - $this + + 275, 89 - - 0 - - - True - - - True + + 251, 111 - 816, 576 - - - ConfigPlanner - - - System.Windows.Forms.MyUserControl, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + 816, 635 \ No newline at end of file diff --git a/GCSViews/ConfigurationView/ConfigPlanner.resx b/GCSViews/ConfigurationView/ConfigPlanner.resx index ccd54f6684..fa6d856aea 100644 --- a/GCSViews/ConfigurationView/ConfigPlanner.resx +++ b/GCSViews/ConfigurationView/ConfigPlanner.resx @@ -117,2414 +117,2435 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - NoControl + + + False - - 535, 254 - - - 43, 13 + + 107, 166 - - - 87 + + 144, 17 - - Sensor + + $this - - label33 + + $this - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + NoControl - + $this - - 33 - - - -1 + + 54 - - 0 + + 61 - - 1 + + 340, 504 - - 2 + + 138, 24 - - 3 + + 66 - - 4 + + 44 - - 5 + + $this - - 6 + + label93 - - 7 + + CHK_disttohomeflightdata - - 8 + + 64 - - 9 + + label101 - - 10 + + -1 - - 25 + + 60 - - 50 + + 107, 349 - - 100 + + 56 - - 584, 251 + + 386, 22 - - 40, 20 + + CMB_ratestatus - - 88 + + 56, 13 - - CMB_ratesensors + + CHK_GDIPlus - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 1 - - $this + + Log Path - - 34 + + 53, 22 True - - NoControl + + 32 - - 9, 38 + + 40, 24 - - 74, 12 + + 330, 254 - - 86 + + NoControl - - Video Format + + NoControl - - label26 + + 76 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 38 - - $this + + 6 - - 35 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 107, 35 + + 107, 326 - - 408, 20 + + NOTE: Set the low level of SEVERITY to speak - - 44 + + 949, 591 - - CMB_videoresolutions + + 50 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + label107 - - $this + + NoControl - - 36 + + Low Speed - - True + + 104 - - NoControl + + 123 - - 9, 350 + + 116 - - 29, 12 + + Custom - - 84 + + 62 - - HUD + + $this - - label12 + + CMB_videoresolutions - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - + $this - - 37 + + 23 - - NoControl + + 22, 13 - - 107, 349 + + 77 - - 220, 17 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 85 + + 20 - - GDI+ (old type/no HW acceleration) + + 40 - - CHK_GDIPlus + + 9, 142 - + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + True + + $this - - 38 + + 51, 16 - - True + + 95, 16 - + NoControl - - 9, 327 + + 51 - - 57, 12 + + $this - - 82 + + 88 - - Waypoints + + 496, 527 - - label24 + + 93, 20 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 115 - + + chk_slowMachine + + $this - - 39 + + True - - NoControl + + Joystick Setup - - 107, 326 + + $this - - 177, 17 + + 559, 89 - - 83 + + Enable Speech - - Load Waypoints on connect? + + 9, 424 - - CHK_loadwponconnect + + 81, 17 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + False - - $this + + 21 - - 40 + + System.Windows.Forms.MyUserControl, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - True + + Telemetry Rates - - NoControl + + CHK_maprotation - - 9, 301 + + NoControl - - 72, 12 + + 186, 20 - - 81 + + OptOut Anon Stats - - Track Length + + $this - - label23 + + 42 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - + $this - - 41 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 107, 300 + + MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 67, 19 + + 9, 373 - - 80 + + True - - NUM_tracklength + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + 9 - - 42 + + 81 - - True + + 9, 327 - - NoControl + + Auto Commit Params - - 671, 89 + + CHK_params_bg - - 83, 16 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 79 + + NoControl - - Alt Warning + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - False + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - CHK_speechaltwarning + + label95 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - + $this - - 43 + + 113 - - True + + 107, 62 - + NoControl - - 9, 278 - - - 81, 12 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 45 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - Connect Reset + + Alt Units - - label108 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 39 - - $this + + True - - 44 + + 108, 20 - - NoControl + + 249, 421 - - 107, 277 + + 14 - - 217, 17 + + BUT_videostart - - 46 + + 107, 35 - - Reset on USB Connect (toggle DTR) + + 107, 195 - - CHK_resetapmonconnect + + 50 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 25 - + $this - - 45 + + 9 - - Bottom, Left + + 67 - - NoControl + + 47, 16 - - 106, 571 + + 100 - - 155, 17 + + 3 - - 47 - - - Mavlink Message Debug - - - CHK_mavdebug + + True - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - + $this - - 46 - - - NoControl - 461, 254 - - 22, 13 + + 56, 13 - - 48 + + 16 - - RC + + ConfigPlanner - - label107 + + 87 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 439, 6 - - $this + + CMB_videosources - - 47 + + NoControl - - -1 + + 157, 31 - - 0 + + 37 - - 1 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 2 + + 60, 16 - - 3 + + NoControl - - 4 + + $this - - 5 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 6 + + GDI+ (old type/no HW acceleration) - - 7 + + CMB_speedunits - - 8 + + True - - 9 + + $this - - 10 + + NoControl - - 25 + + 95 - - 35 + + NoControl - - 50 + + 75, 23 - - 489, 251 + + label104 - - 40, 20 + + 9, 477 - - 49 + + NoControl - - CMB_raterc + + 212, 89 - + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + $this - - 48 - - - NoControl - - - 330, 254 + + 75, 23 - - 79, 13 + + 9, 38 - - 50 + + NoControl - - Mode/Status + + CMB_raterc - - label104 + + 129, 17 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - + $this - - 49 - - - NoControl + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 220, 254 - - 56, 13 + + $this - - 51 + + 17 - - Position + + label5 - - label103 + + 241, 31 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CHK_Password + + + label24 $this - - 50 + + 44 - - NoControl + + 107, 222 - - 104, 254 + + $this - - 56, 13 + + 43 - - 52 + + 63, 16 - - Attitude + + CHK_resetapmonconnect - - label102 + + 107, 89 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CHK_speechbattery - + + 92 + + $this - - 51 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - True + + label12 - - NoControl + + CMB_rateattitude - - 9, 254 + + Map Follow - - 90, 12 + + False - - 53 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - Telemetry Rates + + 99, 23 - - label101 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this + + Runing on a slow computer - - 52 + + 11 - - -1 + + 9, 398 - - 0 + + 228, 20 - - 1 + + 120 - - 2 + + 496, 504 - - 3 + + 138, 24 - - 4 + + 480, 198 - - 5 + + 55 - - 6 + + 671, 504 - - 7 + + label96 - - 8 + + Alt Warning - - 9 + + 100 - - 10 + + 1 - - 25 + + 41 - - 35 + + 119, 20 - - 50 + + 489, 251 - - 415, 251 + + $this - - 40, 20 + + 107, 448 - - 54 + + NoControl - - CMB_ratestatus + + 9, 141 - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 53 + + 71 - - -1 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 0 + + 584, 251 - - 1 + + 25 - - 2 + + 75, 20 - - 3 + + 83 - - 4 + + Bottom, Left - - 5 + + True - - 6 + + 56 - - 7 + + CMB_osdcolor - - 8 + + 340, 571 - - 9 + + True - - 10 + + NoControl - - 20 + + 520, 10 50 - - 100 + + NoControl - - 282, 251 + + $this - - 40, 20 + + 107, 395 - - 55 + + 8 - - CMB_rateposition + + 29 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - $this + + Show Airports - - 54 + + 35 - - -1 + + CHK_speechaltwarning - - 0 + + Video Device - - 1 + + -1 - - 2 + + True - - 3 + + 760, 89 - - 4 + + 107, 277 - - 5 + + 85 - - 6 + + 48 - - 7 + + 71, 16 - - 8 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 9 + + 65 + + + $this 10 - - 50 - - - 100 + + 45 - - 166, 251 + + 61 - - 40, 20 + + NoControl - - 56 + + 43, 13 - - CMB_rateattitude + + 67, 22 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - - $this + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 55 + + 68 - - NoControl + + True - - 480, 198 + + CMB_Layout - - 241, 31 + + 77 - - 57 + + 24 - - NOTE: The Configuration Tab will NOT display these units, as those are raw values. - + + True - - label99 + + $this - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 105 - + + 127 + + + 40, 24 + + $this - - 56 + + 10 - - True + + 107, 372 - - NoControl + + 78 - - 9, 225 + + 408, 24 - - 67, 12 + + 64, 20 - - 58 + + True - - Speed Units + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - label98 + + 40, 24 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Only when Armed - + $this - - 57 + + CHK_mavdebug - - True + + 55, 16 - - NoControl + + 15 - - 9, 198 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 57, 12 + + NoControl - - 59 + + 72 - - Dist Units + + 172, 20 - - label97 + + label92 - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + 332, 89 - - 58 + + 65, 20 - - 107, 222 + + label94 - - 138, 20 + + $this - - 60 + + $this - - CMB_speedunits + + 107, 139 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 9, 11 - + + 8 + + + 75, 23 + + $this - - 59 + + 49 - - 107, 195 + + CMB_rateposition - - 138, 20 + + label3 - - 61 + + 2 - - CMB_distunits + + -1 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + BUT_Vario - + $this - - 60 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - True + + label102 - + NoControl - - 9, 171 + + NoControl - - 49, 12 + + 35 - - 62 + + Browse - - Joystick + + True - - label96 + + $this - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 69 - - $this + + 282, 251 - - 61 + + 37, 16 - - True + + Waypoints - - NoControl + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 9, 90 + + $this - - 42, 12 + + 107, 550 - - 63 + + NoControl - - Speech + + 60 - - label95 + + 46 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Joystick - + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - - 62 + + num_gcsid - - True + + 68 - - NoControl + + Dist to Home - - 559, 89 + + $this - - 106, 16 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 64 - - - Battery Warning + + Enable HUD Overlay - - False + + 7 - - CHK_speechbattery + + 111 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 74 - + $this - - 63 - - - True + + label8 - - NoControl + + 0 - - 469, 89 + + 1 - - 84, 16 + + 2 - - 65 + + 3 - - 30s Interval + + 4 - - False + + 5 - - CHK_speechcustom + + 89, 16 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + HUD - - $this + + 98 - - 64 + + CHK_showairports - - True + + 121, 20 - - NoControl + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 408, 89 + + 57 - - 55, 16 + + 100 - - 66 + + 59 - - Mode + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - False + + CMB_theme - - CHK_speechmode + + 100 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + -1 - + $this - - 65 - - - True + + $this - + NoControl - - 332, 89 - - - 70, 16 - - - 67 - - - Waypoint - - - False + + Connect Reset - - CHK_speechwaypoint + + 97, 20 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - + $this - - 66 + + 340, 550 - - True + + 138, 23 - + NoControl - - 9, 65 - - - 59, 12 + + 4 - - 68 + + 72 - - OSD Color + + $this - - label94 + + 25 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + $this - - 67 + + 138, 24 - - 107, 62 + + NoControl - - 138, 20 + + chk_tfr - - 69 + + 103 - - CMB_osdcolor + + True - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 104, 254 - - $this + + CMB_distunits - - 68 + + NoControl - - 107, 111 + + 109 - - 138, 20 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 125 + + 117 - - CMB_severity + + label99 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 48 - + $this - - 69 + + 134, 20 - - 107, 139 + + $this - - 138, 20 + + NoControl - - 70 + + 62 - - CMB_language + + 27 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 30 - - $this + + 50 - - 70 + + True + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 True - - NoControl + + 245, 24 - - 9, 142 + + $this - - 68, 12 + + 50 - - 71 + + $this - - UI Language + + NoControl - - label93 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 9, 90 - + $this - - 71 + + 4 - - True + + 408, 89 - - NoControl + + $this - - 107, 89 + + Start - - 99, 16 + + 110 - - 72 + + $this - - Enable Speech + + 0 - - CHK_enablespeech + + label6 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CHK_hudshow - - $this + + BUT_logdirbrowse - - 72 + + 18 - - NoControl + + 10 - - 520, 10 + + $this - - 133, 18 + + CHK_beta - - 73 + + $this - - Enable HUD Overlay + + Track Length - - CHK_hudshow + + NoControl - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - - $this + + 63 - - 73 + + 1 True + + 126 + + + True + + + 55 + NoControl - - 9, 11 - - - 73, 12 + + $this - - 74 + + ADSB - - Video Device + + 53 - - label92 + + NoControl - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 106, 571 - - $this + + 10 - - 74 + + False - - 107, 8 + + 9, 451 - - 245, 20 + + 34 - - 75 + + 88, 16 - - CMB_videosources + + 130, 20 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 13 - + $this - - 75 + + OSD Color - + + 71, 16 + + True - - NoControl + + 217, 17 - - 9, 373 + + 138, 24 - - 63, 12 + + $this + + + 9, 225 89 - - Map Follow - - - label1 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 31 - - + NoControl - - 107, 372 - - - 205, 17 + + 64 - - 90 + + True Map is rotated to follow the plane - - CHK_maprotation + + 90 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 6 - - $this + + 151, 20 - - 32 + + 96 - - NoControl + + 99, 20 - - 180, 303 + + 108 - - 81, 17 + + 3 - - 91 + + 78 - - Dist to Home + + NoControl - - label2 + + 177, 17 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - - $this - - - 29 + + 9, 350 - + NoControl - - 267, 302 + + Mavlink Message Debug - - 129, 17 + + Beta Updates - - 92 + + Speech - - Display in Flightdata + + NoControl - - CHK_disttohomeflightdata + + 9, 301 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - $this + + 52 - - 30 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NoControl + + Testing Screen - - 107, 166 + + 84 - - 99, 23 + + No RC Receiver - - 76 + + 35 - - Joystick Setup + + 22 - - BUT_Joystick + + 59 - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + 138, 24 - - $this + + 51 - - 76 + + 20 - - NoControl + + $this - - 439, 6 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 75, 23 + + 93 - - 77 + + $this - - Stop + + True - - BUT_videostop + + NoControl - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + Mode - - $this + + 1 - - 77 + + Waypoint - + NoControl - - 358, 6 + + 0 - - 75, 23 + + 5 - - 78 + + 6 - - Start + + 3 - - BUT_videostart + + 4 - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + Layout - - $this + + True - - 78 + + 7 - - True + + 8 - - NoControl + + 107, 300 - - 9, 398 + + 0 - - 50, 12 + + 125 - - 93 + + 6 - - Log Path + + NoControl - - label3 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + 85, 16 - - 28 + + 0 - - 107, 395 + + 69 - - 386, 19 + + 65 - - 94 + + BUT_Joystick - - txt_log_dir + + 74 - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 75 - + $this - - 27 + + $this - + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - 496, 393 + + 133, 18 - - 75, 23 + + 58 - - 95 + + 340, 527 - - Browse + + 7 - - BUT_logdirbrowse + + 9, 171 - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + Battery Warning - - $this + + 138, 24 - - 26 + + CMB_ratesensors - - True + + 94 - + NoControl - - 9, 424 + + 8 - - 39, 12 + + 7 - - 96 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - Theme + + 535, 254 - - label4 + + 4 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + -1 - - $this + + 6 - - 25 + + 5 - - 107, 421 + + 0 - - 138, 20 + + True - - 97 + + 2 - - CMB_theme + + 1 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + RC - - 24 + + $this - - NoControl + + $this - - 249, 421 + + label9 - - 75, 20 + + 9 - - 98 + + 107 - - Custom + + 81, 16 - - BUT_themecustom + + chk_shownofly - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + 79, 13 - - $this + + 138, 24 - - 23 + + 107, 501 - - True + + 124 - - NoControl + + 47 - - 760, 89 + + 56, 16 - - 87, 16 + + 166, 251 - - 99 + + 52 - - Arm/Disarm + + 228, 527 - - False + + 76 CHK_speecharmdisarm - + + chk_temp + + + 79 + + + 107, 475 + + + 47 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + CMB_severity + + + NoControl + + $this - - 22 + + 102 - + + Video Format + + + 33 + + + label23 + + + Sensor + + + 49 + + NoControl - - 107, 501 + + NoControl - - 99, 20 + + NoControl - - 100 + + 73 - - Start/Stop Vario + + 671, 89 - - BUT_Vario + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + True + + + 66 + + + NoControl + + + label1 + + + 26 + + + $this + + + False - - MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null + + 94, 20 - + $this - - 21 - - - True + + 107, 421 - - NoControl + + 155, 17 - - 107, 527 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 121, 16 + + Params Download in BackGround - - 102 + + 7 - - OptOut Anon Stats + + 31 - - chk_analytics + + 122 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - $this + + CHK_speechcustom - - 20 + + 82 - - True + + 97 - + NoControl - - 228, 527 + + MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 94, 16 + + 12 - - 103 + + NoControl - - Beta Updates + + 30s Interval - - CHK_beta + + 46 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 598, 528 - - $this + + 63, 20 - - 19 + + 8 - - True + + CHK_loadwponconnect - - NoControl + + Theme - - 340, 504 + + 71 - - 151, 16 + + True - - 104 + + 9 - - Password Protect Config + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - CHK_Password + + 19 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 119 - - $this + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 18 + + 118 - - True + + 2 - + NoControl - - 853, 89 + + 252, 108 - - 79, 16 + + NoControl - - 105 + + Start/Stop Vario - - Low Speed + + 57 - - False + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - CHK_speechlowspeed + + NoControl - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + chk_ADSB - + $this - - 17 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + True - - NoControl + + 10 - - 496, 504 + + UI Language - - 96, 16 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 107 + + Load Waypoints on connect? - - Show Airports + + 249, 198 - - CHK_showairports + + 75 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + $this - - 16 + + 107, 111 - + + 121 + + True - - NoControl + + 70 598, 504 - - 55, 16 + + 109, 20 - - 108 + + 50 - - ADSB + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - chk_ADSB + + 9, 278 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CMB_altunits - - $this + + GCS ID - - 15 + + label108 - - True + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + label33 + + + 58 + + + 94, 20 + + NoControl - - 496, 527 + + 91 + + + False + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 54, 16 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 109 + + 358, 6 TFR's - - chk_tfr - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this + + 86 - - 14 + + 40, 24 - - Bottom, Left + + 9, 65 - - NoControl + + $this - - 340, 571 + + $this - - 144, 17 + + 67 - - 110 + + 9 - - Testing Screen + + Stop - - chk_temp + + True - + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this - - - 13 + + NoControl True - - NoControl - - - 340, 527 - - - 107, 16 + + 63, 20 - - 111 + + $this - - No RC Receiver + + Reset on USB Connect (toggle DTR) - - chk_norcreceiver + + 320, 195 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + 50 - - 12 + + label7 - - 107, 448 + + 107, 16 - - 138, 20 + + label2 - - 113 + + $this - - CMB_Layout + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CHK_speechwaypoint - - $this + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 11 + + Password Protect Config - - True + + 3 - - NoControl + + 36 - - 9, 451 + + label98 - - 39, 12 + + txt_log_dir - - 115 + + 76, 16 - - Layout + + 469, 89 - - label5 + + NoControl - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 180, 303 - - $this + + NUM_tracklength - - 10 + + Display in Flightdata - - True + + CHK_enablespeech - - 598, 528 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 133, 16 + + Position - - 116 + + label97 - - Auto Commit Params + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 CHK_AutoParamCommit - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 80 - - $this + + 107, 8 - - 9 + + 5 - + True - - NoControl + + 107, 527 - - 671, 504 + + 9, 254 - - 58, 16 + + 10 - - 117 + + $this - - No Fly + + 5 - - chk_shownofly + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 853, 89 - - $this + + 9 - - 8 + + 9, 198 - + True - - NoControl + + 45 - - 249, 198 + + CHK_speechmode - - 51, 12 + + 8 - - 118 + + 7 - - Alt Units + + 6 - - label6 + + 5 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 4 - - $this + + 3 - - 6 + + 2 - - 320, 195 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 138, 20 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 119 + + 63 - - CMB_altunits + + 220, 17 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 205, 17 - - $this + + 25 - - 7 + + BUT_videostop - - 107, 475 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 53, 19 + + 53 - - 120 + + 496, 393 - - num_gcsid + + 124, 20 - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Dist Units - - $this + + Arm/Disarm - - 5 + + 83, 20 - + True - - NoControl - - - 9, 477 + + False - - 43, 12 + + MissionPlanner.Controls.MyButton, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - - 121 + + False - - GCS ID + + True - - label7 + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Attitude - + $this - - 4 - - - True + + 40, 24 - + NoControl - - 107, 550 + + chk_norcreceiver - - 194, 16 + + 28 - - 122 + + 2 - - Params Download in BackGround + + CHK_speechlowspeed - - CHK_params_bg + + 50, 16 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Mode/Status - - $this + + CHK_speechArmedOnly - - 3 + + $this - - True + + BUT_themecustom - - NoControl + + chk_analytics - - 340, 550 + + 54 - - 163, 16 + + 415, 251 - - 123 + + 99 - - Runing on a slow computer + + $this - - chk_slowMachine + + $this - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + CMB_language - - $this + + label103 - - 2 + + 73 - - True + + 267, 302 - - NoControl + + No Fly - - 212, 89 + + 70 - - 114, 16 + + label4 - - 124 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - Only when Armed + + $this - - False + + Speed Units - - CHK_speechArmedOnly + + 84, 16 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + $this - - 1 + + label26 - + NoControl - - 252, 108 + + True - - 157, 31 + + Bottom, Left - - 126 + + $this - - NOTE: Set the low level of SEVERITY to speak + + 54, 16 - - label8 + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - + $this - + + NOTE: The Configuration Tab will NOT display these units, as those are raw values. + + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 0 True - - True - - - 949, 591 - - - ConfigPlanner - - - System.Windows.Forms.MyUserControl, MissionPlanner.Controls, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null - + + ko-KR + \ No newline at end of file diff --git a/GCSViews/ConfigurationView/ConfigSerial.cs b/GCSViews/ConfigurationView/ConfigSerial.cs index cbc19c3150..eab67d2385 100644 --- a/GCSViews/ConfigurationView/ConfigSerial.cs +++ b/GCSViews/ConfigurationView/ConfigSerial.cs @@ -20,6 +20,7 @@ public partial class ConfigSerial : MyUserControl, IActivate, IDeactivate private bool _gotUARTNames = false; private bool _gotOptionRules = false; + private int serialPorts = 0; private Dictionary _uartNames = new Dictionary(); private Dictionary _optionRules = new Dictionary(); @@ -160,7 +161,7 @@ public void Activate() } //find the largest numbered serialx_baud param - int serialPorts = 0; + serialPorts = 0; foreach (var param in MainV2.comPort.MAV.param.Keys) { if (param.StartsWith("SERIAL") && param.EndsWith("_BAUD")) @@ -408,7 +409,7 @@ private void doApplyRules(string portName, string v) //But this includes the USB port, so we can only have 4 ports set to mavlink int mavlinkPorts = 0; - for (int i = 1; i <= 5; i++) + for (int i = 1; i <= serialPorts; i++) { string protParamName = "SERIAL" + i.ToString() + "_PROTOCOL"; if (MainV2.comPort.MAV.param[protParamName].Value.ToString() == "1" diff --git a/GCSViews/FlightData.cs b/GCSViews/FlightData.cs index 46ae7561bb..9ae6b7f43f 100644 --- a/GCSViews/FlightData.cs +++ b/GCSViews/FlightData.cs @@ -1692,8 +1692,13 @@ private void BUTactiondo_Click(object sender, EventArgs e) } if (CMB_action.Text == actions.Toggle_Safety_Switch.ToString()) { + var target_system = (byte)MainV2.comPort.sysidcurrent; + if (target_system == 0) { + log.Info("Not toggling safety on sysid 0"); + return; + } var custom_mode = (MainV2.comPort.MAV.cs.sensors_enabled.motor_control && MainV2.comPort.MAV.cs.sensors_enabled.seen) ? 1u : 0u; - var mode = new MAVLink.mavlink_set_mode_t() { custom_mode = custom_mode, target_system = (byte)MainV2.comPort.sysidcurrent }; + var mode = new MAVLink.mavlink_set_mode_t() { custom_mode = custom_mode, target_system = target_system }; MainV2.comPort.setMode(mode, MAVLink.MAV_MODE_FLAG.SAFETY_ARMED); ((Control)sender).Enabled = true; return; @@ -3588,8 +3593,16 @@ private void mainloop() if (Settings.Instance.GetBoolean("CHK_maprotation")) { - // dont holdinvalidation here + ////Check if we have more than one vehicle connected and disable CHK_maprotation if so + if (MainV2.comPort.MAVlist.Count > 1) + { + Settings.Instance["CHK_maprotation"] = "false"; + //And set maprotation to zero + BeginInvoke((Action)delegate { gMapControl1.Bearing = 0; }); + } + //gMapControl1.HoldInvalidation = true; setMapBearing(); + } if (route == null) @@ -4340,14 +4353,15 @@ private void quickView_DoubleClick(object sender, EventArgs e) Form selectform = new Form { Name = "select", - Width = 50, - Height = 50, + Width = MainV2.instance.Width - 100, + Height = MainV2.instance.Height - 100, Text = "Display This", - AutoSize = true, + AutoSize = false, StartPosition = FormStartPosition.CenterParent, MaximizeBox = false, MinimizeBox = false, - AutoScroll = true + AutoScroll = true, + FormBorderStyle = FormBorderStyle.FixedDialog }; ThemeManager.ApplyThemeTo(selectform); diff --git a/GCSViews/SoftwareConfig.cs b/GCSViews/SoftwareConfig.cs index 764279f5c9..9cb0bf9199 100644 --- a/GCSViews/SoftwareConfig.cs +++ b/GCSViews/SoftwareConfig.cs @@ -94,7 +94,7 @@ private void SoftwareConfig_Load(object sender, EventArgs e) start = AddBackstageViewPage(typeof(ConfigAntennaTracker), Strings.ExtendedTuning); } - if (MainV2.DisplayConfiguration.displayBasicTuning) + if (MainV2.DisplayConfiguration.displayStandardParams) { AddBackstageViewPage(typeof(ConfigFriendlyParams), Strings.StandardParams); } @@ -122,7 +122,7 @@ private void SoftwareConfig_Load(object sender, EventArgs e) if (MainV2.DisplayConfiguration.displayFullParamList) { if(!MainV2.comPort.BaseStream.IsOpen || gotAllParams) - AddBackstageViewPage(typeof(ConfigRawParams), Strings.FullParameterList, null, true); + AddBackstageViewPage(typeof(ConfigRawParams), Strings.FullParameterList, null, false); } if (MainV2.comPort.BaseStream.IsOpen) { diff --git a/Joystick/JoystickSetup.cs b/Joystick/JoystickSetup.cs index ad1a4d5576..4baff5bf98 100644 --- a/Joystick/JoystickSetup.cs +++ b/Joystick/JoystickSetup.cs @@ -95,6 +95,13 @@ private void Joystick_Load(object sender, EventArgs e) return (short)MainV2.comPort.MAV.cs.GetType().GetField("rcoverridech" + ax.ChannelNo) .GetValue(MainV2.comPort.MAV.cs); }; + ax.Expo = () => + { + if (int.TryParse(ax.ExpoValue, out int expoValue)) + { + MainV2.joystick?.setExpo(ax.ChannelNo, expoValue); + } + }; Controls.Add(ax); diff --git a/Log/LogBrowse.cs b/Log/LogBrowse.cs index c2049f7c73..2e073a37cf 100644 --- a/Log/LogBrowse.cs +++ b/Log/LogBrowse.cs @@ -316,9 +316,44 @@ private void LogBrowse_Load(object sender, EventArgs e) ThreadPool.QueueUserWorkItem(o => LoadLog(logfilename)); } + zg1.ContextMenuBuilder += Zg1_ContextMenuBuilder; + log.Info("LogBrowse_Load Done"); } + private void Zg1_ContextMenuBuilder(ZedGraphControl sender, ContextMenuStrip menuStrip, Point mousePt, ZedGraphControl.ContextMenuObjectState objState) + { + menuStrip.Items.Add(new ToolStripMenuItem("Properties MasterPane", null, (c, e) => + { + var propertyGrid1 = new PropertyGrid(); + propertyGrid1.Width = 500; + propertyGrid1.Height = 800; + propertyGrid1.SelectedObject = zg1.MasterPane; + + propertyGrid1.ShowUserControl(); + })); + + menuStrip.Items.Add(new ToolStripMenuItem("Properties YAxis", null, (c, e) => + { + var propertyGrid1 = new PropertyGrid(); + propertyGrid1.Width = 500; + propertyGrid1.Height = 800; + propertyGrid1.SelectedObject = zg1.GraphPane.YAxis.Scale; + + propertyGrid1.ShowUserControl(); + })); + + menuStrip.Items.Add(new ToolStripMenuItem("Properties YAxis2", null, (c, e) => + { + var propertyGrid1 = new PropertyGrid(); + propertyGrid1.Width = 500; + propertyGrid1.Height = 800; + propertyGrid1.SelectedObject = zg1.GraphPane.Y2Axis.Scale; + + propertyGrid1.ShowUserControl(); + })); + } + public void LoadLog(string FileName) { while (!this.IsHandleCreated) @@ -3649,9 +3684,19 @@ private void chk_datagrid_CheckedChanged(object sender1, EventArgs e) } else { + dataGridView1.Visible = false; dataGridView1.VirtualMode = true; dataGridView1.ColumnCount = colcount; + for(int u=0;u < dataGridView1.ColumnCount; u++) + { + dataGridView1.Columns[u].Visible = false; + } dataGridView1.RowCount = logdata.Count; + for (int u = 0; u < dataGridView1.ColumnCount; u++) + { + dataGridView1.Columns[u].Visible = true; + } + dataGridView1.Visible = true; log.Info("datagrid size set " + (GC.GetTotalMemory(false) / 1024.0 / 1024.0)); } @@ -3763,8 +3808,8 @@ private void chk_params_CheckedChanged(object sender, EventArgs e) foreach (var msg in logdata.GetEnumeratorType("PARM")) { double value = double.Parse(msg["Value"], CultureInfo.InvariantCulture); - decimal tmp; - decimal? default_value = has_defaults && decimal.TryParse(msg["Default"], out tmp) ? (decimal?)tmp : null; + double tmp; + double? default_value = has_defaults && double.TryParse(msg["Default"], out tmp) ? (double?)tmp : null; MAVLink.MAVLinkParam sourceItem = new MAVLink.MAVLinkParam(msg["Name"], value, MAVLink.MAV_PARAM_TYPE.REAL32, default_value); // Lookup the next item in the target list @@ -3846,5 +3891,11 @@ private void exportFilesToolStripMenuItem_Click(object sender, EventArgs e) } } } + + private class MetaData + { + public double Min; + public double Max; + } } } \ No newline at end of file diff --git a/MainV2.cs b/MainV2.cs index 107958546a..aa0fc37f82 100644 --- a/MainV2.cs +++ b/MainV2.cs @@ -38,6 +38,7 @@ using MissionPlanner.Joystick; using System.Net; using Newtonsoft.Json; +using DroneCAN; namespace MissionPlanner { @@ -974,6 +975,10 @@ public MainV2() try { DisplayConfiguration = Settings.Instance.GetDisplayView("displayview"); + //Force new view in case of saved view in config.xml + DisplayConfiguration.displayAdvancedParams = false; + DisplayConfiguration.displayStandardParams = false; + DisplayConfiguration.displayFullParamList = true; } catch { @@ -1763,6 +1768,128 @@ public void doConnect(MAVLinkInterface comPort, string portname, string baud, bo } }); + // check for newer firmware - can peripheral + if (showui) + Task.Run(() => + { + try + { + List buses = new List { 1, 2 }; + foreach (var bus in buses) + { + using (var port = new CommsInjection()) + { + var can = new DroneCAN.DroneCAN(); + can.SourceNode = 127; + + port.ReadBufferUpdate += (o, i) => { }; + port.WriteCallback += (o, bytes) => + { + var lines = ASCIIEncoding.ASCII.GetString(bytes.ToArray()) + .Split(new[] { '\r' }, StringSplitOptions.RemoveEmptyEntries); + + foreach (var line in lines) + { + can.ReadMessageSLCAN(line); + + } + + }; + + // mavlink to slcan + var canref = MainV2.comPort.SubscribeToPacketType(MAVLink.MAVLINK_MSG_ID.CAN_FRAME, (m) => + { + if (m.msgid == (uint)MAVLink.MAVLINK_MSG_ID.CAN_FRAME) + { + var canfd = false; + var pkt = (MAVLink.mavlink_can_frame_t)m.data; + var cf = new CANFrame(BitConverter.GetBytes(pkt.id)); + var length = pkt.len; + var payload = new CANPayload(pkt.data); + + var ans2 = String.Format("{0}{1}{2}{3}\r", canfd ? 'B' : 'T', cf.ToHex(), length.ToString("X") + , payload.ToHex(DroneCAN.DroneCAN.dlcToDataLength(length))); + + port.AppendBuffer(ASCIIEncoding.ASCII.GetBytes(ans2)); + } + else if (m.msgid == (uint)MAVLink.MAVLINK_MSG_ID.CANFD_FRAME) + { + var canfd = true; + var pkt = (MAVLink.mavlink_canfd_frame_t)m.data; + var cf = new CANFrame(BitConverter.GetBytes(pkt.id)); + var length = pkt.len; + var payload = new CANPayload(pkt.data); + + var ans2 = String.Format("{0}{1}{2}{3}\r", canfd ? 'B' : 'T', cf.ToHex(), length.ToString("X") + , payload.ToHex(DroneCAN.DroneCAN.dlcToDataLength(length))); + + port.AppendBuffer(ASCIIEncoding.ASCII.GetBytes(ans2)); + } + + return true; + }, (byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent, true); + + can.NodeAdded += (id, status) => + { + Console.WriteLine(id + " Node status seen"); + // get node info + DroneCAN.DroneCAN.uavcan_protocol_GetNodeInfo_req gnireq = new DroneCAN.DroneCAN.uavcan_protocol_GetNodeInfo_req() { }; + + var slcan = can.PackageMessageSLCAN((byte)id, 30, 0, gnireq); + + can.WriteToStreamSLCAN(slcan); + }; + + // be invisible + can.NodeStatus = false; + can.StartSLCAN(port.BaseStream); + + //start on bus + var ans = MainV2.comPort.doCommand((byte)MainV2.comPort.sysidcurrent, + (byte)MainV2.comPort.compidcurrent, MAVLink.MAV_CMD.CAN_FORWARD, bus, 0, 0, 0, 0, 0, 0, + false); + + Thread.Sleep(5000); + + // stop + MainV2.comPort.doCommand((byte)MainV2.comPort.sysidcurrent, + (byte)MainV2.comPort.compidcurrent, MAVLink.MAV_CMD.CAN_FORWARD, 0, 0, 0, 0, 0, 0, 0, + false); + + foreach (var node in can.NodeInfo) + { + var devicename = can.GetNodeName((byte)node.Key); + var githash = can.NodeInfo[node.Key].software_version.vcs_commit.ToString("X"); + //Version and githash + + var option = APFirmware.Manifest.Firmware.Where(a => + a.MavFirmwareVersionType == APFirmware.RELEASE_TYPES.OFFICIAL.ToString() && + a.VehicleType == "AP_Periph" && + a.Format == "bin" && + a.MavType == "CAN_PERIPHERAL" && + a.MavFirmwareVersionMajor >= node.Value.software_version.major && + a.MavFirmwareVersionMinor >= node.Value.software_version.minor && + node.Value.software_version.major != 0 && + node.Value.software_version.minor != 0 && + devicename.EndsWith(a.Platform) && + !a.GitSha.StartsWith(githash, StringComparison.InvariantCultureIgnoreCase) + ).FirstOrDefault(); + if (option != default(APFirmware.FirmwareInfo)) + { + Common.MessageShowAgain("New firmware", "New firmware for " + devicename + " " + option.MavFirmwareVersion + " " + option.GitSha + "\nUpdate via the dronecan screen"); + } + } + + MainV2.comPort.UnSubscribeToPacketType(canref); + } + } + } + catch (Exception ex) + { + log.Error(ex); + } + }); + this.BeginInvokeIfRequired(() => { _connectionControl.UpdateSysIDS(); @@ -3309,36 +3436,39 @@ protected override void OnLoad(EventArgs e) }; AutoConnect.NewVideoStream += (sender, gststring) => { - try + MainV2.instance.BeginInvoke((Action)delegate { - log.Info("AutoConnect.NewVideoStream " + gststring); - GStreamer.gstlaunch = GStreamer.LookForGstreamer(); - - if (!GStreamer.gstlaunchexists) + try { - if (CustomMessageBox.Show( - "A video stream has been detected, but gstreamer has not been configured/installed.\nDo you want to install/config it now?", - "GStreamer", System.Windows.Forms.MessageBoxButtons.YesNo) == - (int) System.Windows.Forms.DialogResult.Yes) + log.Info("AutoConnect.NewVideoStream " + gststring); + GStreamer.gstlaunch = GStreamer.LookForGstreamer(); + + if (!GStreamer.gstlaunchexists) { - GStreamerUI.DownloadGStreamer(); - if (!GStreamer.gstlaunchexists) + if (CustomMessageBox.Show( + "A video stream has been detected, but gstreamer has not been configured/installed.\nDo you want to install/config it now?", + "GStreamer", System.Windows.Forms.MessageBoxButtons.YesNo) == + (int)System.Windows.Forms.DialogResult.Yes) + { + GStreamerUI.DownloadGStreamer(); + if (!GStreamer.gstlaunchexists) + { + return; + } + } + else { return; } } - else - { - return; - } - } - GStreamer.StartA(gststring); - } - catch (Exception ex) - { - log.Error(ex); - } + GStreamer.StartA(gststring); + } + catch (Exception ex) + { + log.Error(ex); + } + }); }; AutoConnect.Start(); @@ -3354,22 +3484,32 @@ protected override void OnLoad(EventArgs e) return; } - if (!videourlseen.Contains(s) && videodetect.Wait(0)) + MainV2.instance.BeginInvoke((Action)delegate { - videourlseen.Add(s); - if (CustomMessageBox.Show( - "A video stream has been detected, Do you want to connect to it? " + s, - "Mavlink Camera", System.Windows.Forms.MessageBoxButtons.YesNo) == - (int) System.Windows.Forms.DialogResult.Yes) + try { - AutoConnect.RaiseNewVideoStream(sender, - String.Format( - "rtspsrc location={0} latency=41 udp-reconnect=1 timeout=0 do-retransmission=false ! application/x-rtp ! decodebin3 ! queue leaky=2 ! videoconvert ! video/x-raw,format=BGRA ! appsink name=outsink sync=false", - s)); - } + if (!videourlseen.Contains(s) && videodetect.Wait(0)) + { + videourlseen.Add(s); + if (CustomMessageBox.Show( + "A video stream has been detected, Do you want to connect to it? " + s, + "Mavlink Camera", System.Windows.Forms.MessageBoxButtons.YesNo) == + (int)System.Windows.Forms.DialogResult.Yes) + { + AutoConnect.RaiseNewVideoStream(sender, + String.Format( + "rtspsrc location={0} latency=41 udp-reconnect=1 timeout=0 do-retransmission=false ! application/x-rtp ! decodebin3 ! queue leaky=2 ! videoconvert ! video/x-raw,format=BGRA ! appsink name=outsink sync=false", + s)); + } - videodetect.Release(); - } + videodetect.Release(); + } + } + catch (Exception ex) + { + log.Error(ex); + } + }); }; diff --git a/MissionPlanner.csproj b/MissionPlanner.csproj index a33c1dcda6..a26bfdbb6f 100644 --- a/MissionPlanner.csproj +++ b/MissionPlanner.csproj @@ -1022,7 +1022,11 @@ + + + + Form Splash.cs @@ -1576,6 +1580,7 @@ Form + UserControl diff --git a/MissionPlanner.sln b/MissionPlanner.sln index 0a43b51d4d..2517a875cb 100644 --- a/MissionPlanner.sln +++ b/MissionPlanner.sln @@ -221,676 +221,337 @@ Project("{9A19103F-16F7-4668-BE54-9A1E7A4F7556}") = "AltitudeAngelWings.Plugin", EndProject Project("{9A19103F-16F7-4668-BE54-9A1E7A4F7556}") = "OpenDroneID_Plugin", "Plugins\OpenDroneID2\OpenDroneID_Plugin.csproj", "{FBE658B3-684D-46E6-8668-50DEF0778538}" EndProject -Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "Bulb", "ExtLibs\LEDBulb\Bulb\Bulb.csproj", "{AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}" +Project("{9A19103F-16F7-4668-BE54-9A1E7A4F7556}") = "Bulb", "ExtLibs\LEDBulb\Bulb\Bulb.csproj", "{AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}" EndProject Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "MissionPlannerTests", "MissionPlannerTests\MissionPlannerTests.csproj", "{0B99EBF2-B964-4AAC-9EC5-76353610AAAE}" EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug|Any CPU = Debug|Any CPU - Debug|x86 = Debug|x86 Release|Any CPU = Release|Any CPU - Release|x86 = Release|x86 EndGlobalSection GlobalSection(ProjectConfigurationPlatforms) = postSolution {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|Any CPU.Build.0 = Debug|Any CPU - {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|x86.ActiveCfg = Debug|Any CPU - {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Debug|x86.Build.0 = Debug|Any CPU {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|Any CPU.ActiveCfg = Release|Any CPU {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|Any CPU.Build.0 = Release|Any CPU - {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|x86.ActiveCfg = Release|Any CPU - {A2E22272-95FE-47B6-B050-9AE7E2055BF5}.Release|x86.Build.0 = Release|Any CPU {E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|x86.ActiveCfg = Debug|Any CPU - {E64A1A41-A5B0-458E-8284-BB63705354DA}.Debug|x86.Build.0 = Debug|Any CPU {E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Any CPU.ActiveCfg = Release|Any CPU - {E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.ActiveCfg = Release|Any CPU - {E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.Build.0 = Release|Any CPU {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Any CPU.Build.0 = Debug|Any CPU - {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|x86.ActiveCfg = Debug|Any CPU - {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|x86.Build.0 = Debug|Any CPU {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Any CPU.ActiveCfg = Release|Any CPU {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Any CPU.Build.0 = Release|Any CPU - {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|x86.ActiveCfg = Release|Any CPU - {76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|x86.Build.0 = Release|Any CPU {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Debug|Any CPU.Build.0 = Debug|Any CPU - {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Debug|x86.ActiveCfg = Debug|Any CPU - {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Debug|x86.Build.0 = Debug|Any CPU {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Release|Any CPU.ActiveCfg = Release|Any CPU {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Release|Any CPU.Build.0 = Release|Any CPU - {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Release|x86.ActiveCfg = Release|Any CPU - {6A6F4345-0A45-413E-B6D6-FD73660DAD4C}.Release|x86.Build.0 = Release|Any CPU {94C380C1-566A-4D86-855B-2E987851BF0A}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {94C380C1-566A-4D86-855B-2E987851BF0A}.Debug|Any CPU.Build.0 = Debug|Any CPU - {94C380C1-566A-4D86-855B-2E987851BF0A}.Debug|x86.ActiveCfg = Debug|Any CPU - {94C380C1-566A-4D86-855B-2E987851BF0A}.Debug|x86.Build.0 = Debug|Any CPU {94C380C1-566A-4D86-855B-2E987851BF0A}.Release|Any CPU.ActiveCfg = Release|Any CPU {94C380C1-566A-4D86-855B-2E987851BF0A}.Release|Any CPU.Build.0 = Release|Any CPU - {94C380C1-566A-4D86-855B-2E987851BF0A}.Release|x86.ActiveCfg = Release|Any CPU - {94C380C1-566A-4D86-855B-2E987851BF0A}.Release|x86.Build.0 = Release|Any CPU {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Debug|Any CPU.Build.0 = Debug|Any CPU - {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Debug|x86.ActiveCfg = Debug|Any CPU - {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Debug|x86.Build.0 = Debug|Any CPU {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Release|Any CPU.ActiveCfg = Release|Any CPU {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Release|Any CPU.Build.0 = Release|Any CPU - {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Release|x86.ActiveCfg = Release|Any CPU - {28D0BEF6-D69C-43AB-A22C-724F116D50EA}.Release|x86.Build.0 = Release|Any CPU {A7AA6037-BF11-473E-94F9-717276FE080C}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {A7AA6037-BF11-473E-94F9-717276FE080C}.Debug|Any CPU.Build.0 = Debug|Any CPU - {A7AA6037-BF11-473E-94F9-717276FE080C}.Debug|x86.ActiveCfg = Debug|Any CPU - {A7AA6037-BF11-473E-94F9-717276FE080C}.Debug|x86.Build.0 = Debug|Any CPU {A7AA6037-BF11-473E-94F9-717276FE080C}.Release|Any CPU.ActiveCfg = Release|Any CPU {A7AA6037-BF11-473E-94F9-717276FE080C}.Release|Any CPU.Build.0 = Release|Any CPU - {A7AA6037-BF11-473E-94F9-717276FE080C}.Release|x86.ActiveCfg = Release|Any CPU - {A7AA6037-BF11-473E-94F9-717276FE080C}.Release|x86.Build.0 = Release|Any CPU {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Debug|Any CPU.Build.0 = Debug|Any CPU - {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Debug|x86.ActiveCfg = Debug|Any CPU - {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Debug|x86.Build.0 = Debug|Any CPU {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Release|Any CPU.ActiveCfg = Release|Any CPU {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Release|Any CPU.Build.0 = Release|Any CPU - {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Release|x86.ActiveCfg = Release|Any CPU - {ABB32A29-AF50-47FA-B243-5FD75A5ABA54}.Release|x86.Build.0 = Release|Any CPU {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Debug|Any CPU.Build.0 = Debug|Any CPU - {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Debug|x86.ActiveCfg = Debug|Any CPU - {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Debug|x86.Build.0 = Debug|Any CPU {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Release|Any CPU.ActiveCfg = Release|Any CPU {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Release|Any CPU.Build.0 = Release|Any CPU - {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Release|x86.ActiveCfg = Release|Any CPU - {59129078-7B12-4198-B93E-0AA08D0BB7ED}.Release|x86.Build.0 = Release|Any CPU {29976BA4-A04D-4A80-A866-098C879C2FDE}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {29976BA4-A04D-4A80-A866-098C879C2FDE}.Debug|Any CPU.Build.0 = Debug|Any CPU - {29976BA4-A04D-4A80-A866-098C879C2FDE}.Debug|x86.ActiveCfg = Debug|Any CPU - {29976BA4-A04D-4A80-A866-098C879C2FDE}.Debug|x86.Build.0 = Debug|Any CPU {29976BA4-A04D-4A80-A866-098C879C2FDE}.Release|Any CPU.ActiveCfg = Release|Any CPU {29976BA4-A04D-4A80-A866-098C879C2FDE}.Release|Any CPU.Build.0 = Release|Any CPU - {29976BA4-A04D-4A80-A866-098C879C2FDE}.Release|x86.ActiveCfg = Release|Any CPU - {29976BA4-A04D-4A80-A866-098C879C2FDE}.Release|x86.Build.0 = Release|Any CPU {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Debug|Any CPU.Build.0 = Debug|Any CPU - {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Debug|x86.ActiveCfg = Debug|Any CPU - {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Debug|x86.Build.0 = Debug|Any CPU {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Release|Any CPU.ActiveCfg = Release|Any CPU {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Release|Any CPU.Build.0 = Release|Any CPU - {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Release|x86.ActiveCfg = Release|Any CPU - {53F12A60-E9CC-44BC-8366-1AE3AB2B547D}.Release|x86.Build.0 = Release|Any CPU {2541686B-1673-43BF-AF89-3163945DB009}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {2541686B-1673-43BF-AF89-3163945DB009}.Debug|Any CPU.Build.0 = Debug|Any CPU - {2541686B-1673-43BF-AF89-3163945DB009}.Debug|x86.ActiveCfg = Debug|Any CPU - {2541686B-1673-43BF-AF89-3163945DB009}.Debug|x86.Build.0 = Debug|Any CPU {2541686B-1673-43BF-AF89-3163945DB009}.Release|Any CPU.ActiveCfg = Release|Any CPU {2541686B-1673-43BF-AF89-3163945DB009}.Release|Any CPU.Build.0 = Release|Any CPU - {2541686B-1673-43BF-AF89-3163945DB009}.Release|x86.ActiveCfg = Release|Any CPU - {2541686B-1673-43BF-AF89-3163945DB009}.Release|x86.Build.0 = Release|Any CPU {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Debug|Any CPU.Build.0 = Debug|Any CPU - {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Debug|x86.ActiveCfg = Debug|Any CPU - {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Debug|x86.Build.0 = Debug|Any CPU {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Release|Any CPU.ActiveCfg = Release|Any CPU {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Release|Any CPU.Build.0 = Release|Any CPU - {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Release|x86.ActiveCfg = Release|Any CPU - {9CA367B8-0B98-49D1-84FB-735E612E3BA9}.Release|x86.Build.0 = Release|Any CPU {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Debug|x86.ActiveCfg = Debug|Any CPU - {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Debug|x86.Build.0 = Debug|Any CPU {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Release|Any CPU.ActiveCfg = Release|Any CPU {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Release|Any CPU.Build.0 = Release|Any CPU - {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Release|x86.ActiveCfg = Release|Any CPU - {B46F6C6C-9184-41AF-8F8B-E0084752CA7C}.Release|x86.Build.0 = Release|Any CPU {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Debug|Any CPU.Build.0 = Debug|Any CPU - {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Debug|x86.ActiveCfg = Debug|Any CPU - {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Debug|x86.Build.0 = Debug|Any CPU {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Release|Any CPU.ActiveCfg = Release|Any CPU {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Release|Any CPU.Build.0 = Release|Any CPU - {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Release|x86.ActiveCfg = Release|Any CPU - {2A8E8AF5-74E7-49DB-A42E-9360FA7A6CC4}.Release|x86.Build.0 = Release|Any CPU {C8B88795-6D01-494D-83AD-6944BD4C5023}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {C8B88795-6D01-494D-83AD-6944BD4C5023}.Debug|Any CPU.Build.0 = Debug|Any CPU - {C8B88795-6D01-494D-83AD-6944BD4C5023}.Debug|x86.ActiveCfg = Debug|Any CPU - {C8B88795-6D01-494D-83AD-6944BD4C5023}.Debug|x86.Build.0 = Debug|Any CPU {C8B88795-6D01-494D-83AD-6944BD4C5023}.Release|Any CPU.ActiveCfg = Release|Any CPU {C8B88795-6D01-494D-83AD-6944BD4C5023}.Release|Any CPU.Build.0 = Release|Any CPU - {C8B88795-6D01-494D-83AD-6944BD4C5023}.Release|x86.ActiveCfg = Release|Any CPU - {C8B88795-6D01-494D-83AD-6944BD4C5023}.Release|x86.Build.0 = Release|Any CPU {825E7A10-390C-4A2B-B3A8-491D14966912}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {825E7A10-390C-4A2B-B3A8-491D14966912}.Debug|Any CPU.Build.0 = Debug|Any CPU - {825E7A10-390C-4A2B-B3A8-491D14966912}.Debug|x86.ActiveCfg = Debug|Any CPU - {825E7A10-390C-4A2B-B3A8-491D14966912}.Debug|x86.Build.0 = Debug|Any CPU {825E7A10-390C-4A2B-B3A8-491D14966912}.Release|Any CPU.ActiveCfg = Release|Any CPU {825E7A10-390C-4A2B-B3A8-491D14966912}.Release|Any CPU.Build.0 = Release|Any CPU - {825E7A10-390C-4A2B-B3A8-491D14966912}.Release|x86.ActiveCfg = Release|Any CPU - {825E7A10-390C-4A2B-B3A8-491D14966912}.Release|x86.Build.0 = Release|Any CPU {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Debug|Any CPU.Build.0 = Debug|Any CPU - {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Debug|x86.ActiveCfg = Debug|Any CPU - {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Debug|x86.Build.0 = Debug|Any CPU {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Release|Any CPU.ActiveCfg = Release|Any CPU {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Release|Any CPU.Build.0 = Release|Any CPU - {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Release|x86.ActiveCfg = Release|Any CPU - {1378A66C-38E4-46F5-A05F-DC04EF7D4D16}.Release|x86.Build.0 = Release|Any CPU {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Debug|Any CPU.Build.0 = Debug|Any CPU - {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Debug|x86.ActiveCfg = Debug|Any CPU - {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Debug|x86.Build.0 = Debug|Any CPU {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Release|Any CPU.ActiveCfg = Release|Any CPU {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Release|Any CPU.Build.0 = Release|Any CPU - {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Release|x86.ActiveCfg = Release|Any CPU - {7F7994CE-823F-4A04-BBEA-D0A3808FF56D}.Release|x86.Build.0 = Release|Any CPU {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|Any CPU.Build.0 = Debug|Any CPU - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|x86.ActiveCfg = Debug|Any CPU - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Debug|x86.Build.0 = Debug|Any CPU {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|Any CPU.ActiveCfg = Release|Any CPU {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|Any CPU.Build.0 = Release|Any CPU - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|x86.ActiveCfg = Release|Any CPU - {664FC484-2A94-4B0D-808F-A71F88E06B11}.Release|x86.Build.0 = Release|Any CPU {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Debug|Any CPU.Build.0 = Debug|Any CPU - {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Debug|x86.ActiveCfg = Debug|Any CPU - {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Debug|x86.Build.0 = Debug|Any CPU {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Release|Any CPU.ActiveCfg = Release|Any CPU {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Release|Any CPU.Build.0 = Release|Any CPU - {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Release|x86.ActiveCfg = Release|Any CPU - {D0C39D9D-BED0-418B-9A5E-713176CAF40C}.Release|x86.Build.0 = Release|Any CPU {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Debug|Any CPU.Build.0 = Debug|Any CPU - {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Debug|x86.ActiveCfg = Debug|Any CPU - {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Debug|x86.Build.0 = Debug|Any CPU {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Release|Any CPU.ActiveCfg = Release|Any CPU {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Release|Any CPU.Build.0 = Release|Any CPU - {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Release|x86.ActiveCfg = Release|Any CPU - {E06DEF77-F933-42FB-AFD7-DB2D0D8D6A98}.Release|x86.Build.0 = Release|Any CPU {ABA78B2E-77C3-4377-8568-9542AC227971}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {ABA78B2E-77C3-4377-8568-9542AC227971}.Debug|Any CPU.Build.0 = Debug|Any CPU - {ABA78B2E-77C3-4377-8568-9542AC227971}.Debug|x86.ActiveCfg = Debug|Any CPU - {ABA78B2E-77C3-4377-8568-9542AC227971}.Debug|x86.Build.0 = Debug|Any CPU {ABA78B2E-77C3-4377-8568-9542AC227971}.Release|Any CPU.ActiveCfg = Release|Any CPU {ABA78B2E-77C3-4377-8568-9542AC227971}.Release|Any CPU.Build.0 = Release|Any CPU - {ABA78B2E-77C3-4377-8568-9542AC227971}.Release|x86.ActiveCfg = Release|Any CPU - {ABA78B2E-77C3-4377-8568-9542AC227971}.Release|x86.Build.0 = Release|Any CPU {B5211B56-CA30-4B2A-843B-832849F18CEA}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {B5211B56-CA30-4B2A-843B-832849F18CEA}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B5211B56-CA30-4B2A-843B-832849F18CEA}.Debug|x86.ActiveCfg = Debug|Any CPU - {B5211B56-CA30-4B2A-843B-832849F18CEA}.Debug|x86.Build.0 = Debug|Any CPU {B5211B56-CA30-4B2A-843B-832849F18CEA}.Release|Any CPU.ActiveCfg = Release|Any CPU {B5211B56-CA30-4B2A-843B-832849F18CEA}.Release|Any CPU.Build.0 = Release|Any CPU - {B5211B56-CA30-4B2A-843B-832849F18CEA}.Release|x86.ActiveCfg = Release|Any CPU - {B5211B56-CA30-4B2A-843B-832849F18CEA}.Release|x86.Build.0 = Release|Any CPU {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Debug|Any CPU.Build.0 = Debug|Any CPU - {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Debug|x86.ActiveCfg = Debug|Any CPU - {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Debug|x86.Build.0 = Debug|Any CPU {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Release|Any CPU.ActiveCfg = Release|Any CPU {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Release|Any CPU.Build.0 = Release|Any CPU - {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Release|x86.ActiveCfg = Release|Any CPU - {BB06DFF7-4F41-4B9D-A3C3-3B6D2B8702B6}.Release|x86.Build.0 = Release|Any CPU {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Debug|x86.ActiveCfg = Debug|Any CPU - {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Debug|x86.Build.0 = Debug|Any CPU {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|Any CPU.ActiveCfg = Release|Any CPU {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|Any CPU.Build.0 = Release|Any CPU - {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|x86.ActiveCfg = Release|Any CPU - {B8943726-04B0-4477-BFDA-E156A0CD98A4}.Release|x86.Build.0 = Release|Any CPU {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Debug|Any CPU.Build.0 = Debug|Any CPU - {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Debug|x86.ActiveCfg = Debug|Any CPU - {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Debug|x86.Build.0 = Debug|Any CPU {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Release|Any CPU.ActiveCfg = Release|Any CPU {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Release|Any CPU.Build.0 = Release|Any CPU - {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Release|x86.ActiveCfg = Release|Any CPU - {CCE510F7-1DA6-40F2-8921-B86ED41BB85E}.Release|x86.Build.0 = Release|Any CPU {65473257-E70F-410B-9269-D0C0F771EA87}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {65473257-E70F-410B-9269-D0C0F771EA87}.Debug|Any CPU.Build.0 = Debug|Any CPU - {65473257-E70F-410B-9269-D0C0F771EA87}.Debug|x86.ActiveCfg = Debug|Any CPU - {65473257-E70F-410B-9269-D0C0F771EA87}.Debug|x86.Build.0 = Debug|Any CPU {65473257-E70F-410B-9269-D0C0F771EA87}.Release|Any CPU.ActiveCfg = Release|Any CPU {65473257-E70F-410B-9269-D0C0F771EA87}.Release|Any CPU.Build.0 = Release|Any CPU - {65473257-E70F-410B-9269-D0C0F771EA87}.Release|x86.ActiveCfg = Release|Any CPU - {65473257-E70F-410B-9269-D0C0F771EA87}.Release|x86.Build.0 = Release|Any CPU {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Debug|Any CPU.Build.0 = Debug|Any CPU - {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Debug|x86.ActiveCfg = Debug|Any CPU - {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Debug|x86.Build.0 = Debug|Any CPU {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Release|Any CPU.ActiveCfg = Release|Any CPU {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Release|Any CPU.Build.0 = Release|Any CPU - {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Release|x86.ActiveCfg = Release|Any CPU - {098F542C-7C70-4B9C-B2E2-AC5DC5E0294B}.Release|x86.Build.0 = Release|Any CPU {CF402948-A3F4-4962-8A57-E40B46759D25}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {CF402948-A3F4-4962-8A57-E40B46759D25}.Debug|Any CPU.Build.0 = Debug|Any CPU - {CF402948-A3F4-4962-8A57-E40B46759D25}.Debug|x86.ActiveCfg = Debug|Any CPU - {CF402948-A3F4-4962-8A57-E40B46759D25}.Debug|x86.Build.0 = Debug|Any CPU {CF402948-A3F4-4962-8A57-E40B46759D25}.Release|Any CPU.ActiveCfg = Release|Any CPU {CF402948-A3F4-4962-8A57-E40B46759D25}.Release|Any CPU.Build.0 = Release|Any CPU - {CF402948-A3F4-4962-8A57-E40B46759D25}.Release|x86.ActiveCfg = Release|Any CPU - {CF402948-A3F4-4962-8A57-E40B46759D25}.Release|x86.Build.0 = Release|Any CPU {766FCF85-4809-44DB-B316-6C4902C65245}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {766FCF85-4809-44DB-B316-6C4902C65245}.Debug|Any CPU.Build.0 = Debug|Any CPU - {766FCF85-4809-44DB-B316-6C4902C65245}.Debug|x86.ActiveCfg = Debug|Any CPU - {766FCF85-4809-44DB-B316-6C4902C65245}.Debug|x86.Build.0 = Debug|Any CPU {766FCF85-4809-44DB-B316-6C4902C65245}.Release|Any CPU.ActiveCfg = Release|Any CPU {766FCF85-4809-44DB-B316-6C4902C65245}.Release|Any CPU.Build.0 = Release|Any CPU - {766FCF85-4809-44DB-B316-6C4902C65245}.Release|x86.ActiveCfg = Release|Any CPU - {766FCF85-4809-44DB-B316-6C4902C65245}.Release|x86.Build.0 = Release|Any CPU {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Debug|Any CPU.Build.0 = Debug|Any CPU - {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Debug|x86.ActiveCfg = Debug|Any CPU - {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Debug|x86.Build.0 = Debug|Any CPU {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Release|Any CPU.ActiveCfg = Release|Any CPU {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Release|Any CPU.Build.0 = Release|Any CPU - {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Release|x86.ActiveCfg = Release|Any CPU - {13D2EC90-C41F-48A1-AADA-859B6DC24EDC}.Release|x86.Build.0 = Release|Any CPU {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Debug|Any CPU.Build.0 = Debug|Any CPU - {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Debug|x86.ActiveCfg = Debug|Any CPU - {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Debug|x86.Build.0 = Debug|Any CPU {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Release|Any CPU.ActiveCfg = Release|Any CPU {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Release|Any CPU.Build.0 = Release|Any CPU - {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Release|x86.ActiveCfg = Release|Any CPU - {DFA3C3B7-F098-4567-A780-A37DC52CA577}.Release|x86.Build.0 = Release|Any CPU {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Debug|Any CPU.Build.0 = Debug|Any CPU - {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Debug|x86.ActiveCfg = Debug|Any CPU - {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Debug|x86.Build.0 = Debug|Any CPU {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Release|Any CPU.ActiveCfg = Release|Any CPU {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Release|Any CPU.Build.0 = Release|Any CPU - {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Release|x86.ActiveCfg = Release|Any CPU - {F4B60F03-F4C8-42CD-A46D-712838DC184B}.Release|x86.Build.0 = Release|Any CPU {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Debug|Any CPU.Build.0 = Debug|Any CPU - {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Debug|x86.ActiveCfg = Debug|Any CPU - {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Debug|x86.Build.0 = Debug|Any CPU {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Release|Any CPU.ActiveCfg = Release|Any CPU {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Release|Any CPU.Build.0 = Release|Any CPU - {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Release|x86.ActiveCfg = Release|Any CPU - {FF6AA762-7AD3-4F38-94B1-EA75D7B1F217}.Release|x86.Build.0 = Release|Any CPU {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Debug|Any CPU.Build.0 = Debug|Any CPU - {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Debug|x86.ActiveCfg = Debug|Any CPU - {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Debug|x86.Build.0 = Debug|Any CPU {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Release|Any CPU.ActiveCfg = Release|Any CPU {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Release|Any CPU.Build.0 = Release|Any CPU - {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Release|x86.ActiveCfg = Release|Any CPU - {624AFC60-565F-4F01-BD51-BCCE7AA09BE9}.Release|x86.Build.0 = Release|Any CPU {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Debug|Any CPU.Build.0 = Debug|Any CPU - {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Debug|x86.ActiveCfg = Debug|Any CPU - {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Debug|x86.Build.0 = Debug|Any CPU {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Release|Any CPU.ActiveCfg = Release|Any CPU {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Release|Any CPU.Build.0 = Release|Any CPU - {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Release|x86.ActiveCfg = Release|Any CPU - {BB4C8021-B5E1-4DE2-82CB-14BDFB9837E4}.Release|x86.Build.0 = Release|Any CPU {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Debug|Any CPU.Build.0 = Debug|Any CPU - {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Debug|x86.ActiveCfg = Debug|Any CPU - {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Debug|x86.Build.0 = Debug|Any CPU {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Release|Any CPU.ActiveCfg = Release|Any CPU {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Release|Any CPU.Build.0 = Release|Any CPU - {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Release|x86.ActiveCfg = Release|Any CPU - {6C4FF9C3-7AFF-4274-B8FC-4A93A1FAADEA}.Release|x86.Build.0 = Release|Any CPU {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Debug|Any CPU.Build.0 = Debug|Any CPU - {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Debug|x86.ActiveCfg = Debug|Any CPU - {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Debug|x86.Build.0 = Debug|Any CPU {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Release|Any CPU.ActiveCfg = Release|Any CPU {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Release|Any CPU.Build.0 = Release|Any CPU - {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Release|x86.ActiveCfg = Release|Any CPU - {CA6345D3-7A6D-478B-A0ED-A58E50DCAA83}.Release|x86.Build.0 = Release|Any CPU {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Debug|Any CPU.Build.0 = Debug|Any CPU - {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Debug|x86.ActiveCfg = Debug|Any CPU - {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Debug|x86.Build.0 = Debug|Any CPU {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Release|Any CPU.ActiveCfg = Release|Any CPU {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Release|Any CPU.Build.0 = Release|Any CPU - {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Release|x86.ActiveCfg = Release|Any CPU - {A0DE147B-144C-4A34-8D46-9394570AD7E8}.Release|x86.Build.0 = Release|Any CPU {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Debug|Any CPU.Build.0 = Debug|Any CPU - {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Debug|x86.ActiveCfg = Debug|Any CPU - {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Debug|x86.Build.0 = Debug|Any CPU {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Release|Any CPU.ActiveCfg = Release|Any CPU {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Release|Any CPU.Build.0 = Release|Any CPU - {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Release|x86.ActiveCfg = Release|Any CPU - {785380E0-CEB9-4C34-82E5-60D0E33E848E}.Release|x86.Build.0 = Release|Any CPU {B994D8D2-C052-4616-9D20-386640C7387F}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {B994D8D2-C052-4616-9D20-386640C7387F}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B994D8D2-C052-4616-9D20-386640C7387F}.Debug|x86.ActiveCfg = Debug|Any CPU - {B994D8D2-C052-4616-9D20-386640C7387F}.Debug|x86.Build.0 = Debug|Any CPU {B994D8D2-C052-4616-9D20-386640C7387F}.Release|Any CPU.ActiveCfg = Release|Any CPU {B994D8D2-C052-4616-9D20-386640C7387F}.Release|Any CPU.Build.0 = Release|Any CPU - {B994D8D2-C052-4616-9D20-386640C7387F}.Release|x86.ActiveCfg = Release|Any CPU - {B994D8D2-C052-4616-9D20-386640C7387F}.Release|x86.Build.0 = Release|Any CPU {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Debug|Any CPU.Build.0 = Debug|Any CPU - {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Debug|x86.ActiveCfg = Debug|Any CPU - {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Debug|x86.Build.0 = Debug|Any CPU {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Release|Any CPU.ActiveCfg = Release|Any CPU {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Release|Any CPU.Build.0 = Release|Any CPU - {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Release|x86.ActiveCfg = Release|Any CPU - {6D4F97A1-D0A0-44EC-B2A3-F5C954209444}.Release|x86.Build.0 = Release|Any CPU {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Debug|Any CPU.Build.0 = Debug|Any CPU - {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Debug|x86.ActiveCfg = Debug|Any CPU - {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Debug|x86.Build.0 = Debug|Any CPU {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Release|Any CPU.ActiveCfg = Release|Any CPU {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Release|Any CPU.Build.0 = Release|Any CPU - {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Release|x86.ActiveCfg = Release|Any CPU - {993DB853-EC9F-45D5-AD2C-BA008B72995B}.Release|x86.Build.0 = Release|Any CPU {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Debug|Any CPU.Build.0 = Debug|Any CPU - {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Debug|x86.ActiveCfg = Debug|Any CPU - {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Debug|x86.Build.0 = Debug|Any CPU {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Release|Any CPU.ActiveCfg = Release|Any CPU {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Release|Any CPU.Build.0 = Release|Any CPU - {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Release|x86.ActiveCfg = Release|Any CPU - {78AC6375-28AF-4175-9F20-B5099C92EA2B}.Release|x86.Build.0 = Release|Any CPU {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Debug|x86.ActiveCfg = Debug|Any CPU - {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Debug|x86.Build.0 = Debug|Any CPU {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Release|Any CPU.ActiveCfg = Release|Any CPU {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Release|Any CPU.Build.0 = Release|Any CPU - {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Release|x86.ActiveCfg = Release|Any CPU - {B6054E5B-362C-4298-8F20-6BA5BF1A859E}.Release|x86.Build.0 = Release|Any CPU {E2CE55F4-53FB-48C3-A8BE-34161961FD2A}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {E2CE55F4-53FB-48C3-A8BE-34161961FD2A}.Debug|x86.ActiveCfg = Debug|Any CPU - {E2CE55F4-53FB-48C3-A8BE-34161961FD2A}.Debug|x86.Build.0 = Debug|Any CPU {E2CE55F4-53FB-48C3-A8BE-34161961FD2A}.Release|Any CPU.ActiveCfg = Release|Any CPU - {E2CE55F4-53FB-48C3-A8BE-34161961FD2A}.Release|x86.ActiveCfg = Release|Any CPU - {E2CE55F4-53FB-48C3-A8BE-34161961FD2A}.Release|x86.Build.0 = Release|Any CPU {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Debug|Any CPU.Build.0 = Debug|Any CPU - {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Debug|x86.ActiveCfg = Debug|Any CPU - {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Debug|x86.Build.0 = Debug|Any CPU {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Release|Any CPU.ActiveCfg = Release|Any CPU {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Release|Any CPU.Build.0 = Release|Any CPU - {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Release|x86.ActiveCfg = Release|Any CPU - {A7C98A7E-1BCB-4A38-AAC4-2EEC63A5BC5C}.Release|x86.Build.0 = Release|Any CPU {94836116-0CD5-4EA9-8049-447FEA886406}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {94836116-0CD5-4EA9-8049-447FEA886406}.Debug|Any CPU.Build.0 = Debug|Any CPU - {94836116-0CD5-4EA9-8049-447FEA886406}.Debug|x86.ActiveCfg = Debug|Any CPU - {94836116-0CD5-4EA9-8049-447FEA886406}.Debug|x86.Build.0 = Debug|Any CPU {94836116-0CD5-4EA9-8049-447FEA886406}.Release|Any CPU.ActiveCfg = Release|Any CPU {94836116-0CD5-4EA9-8049-447FEA886406}.Release|Any CPU.Build.0 = Release|Any CPU - {94836116-0CD5-4EA9-8049-447FEA886406}.Release|x86.ActiveCfg = Release|Any CPU - {94836116-0CD5-4EA9-8049-447FEA886406}.Release|x86.Build.0 = Release|Any CPU {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Debug|Any CPU.Build.0 = Debug|Any CPU - {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Debug|x86.ActiveCfg = Debug|Any CPU - {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Debug|x86.Build.0 = Debug|Any CPU {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Release|Any CPU.ActiveCfg = Release|Any CPU {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Release|Any CPU.Build.0 = Release|Any CPU - {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Release|x86.ActiveCfg = Release|Any CPU - {077E19BA-4129-4AAE-8FCD-34D6FAF85B78}.Release|x86.Build.0 = Release|Any CPU {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Debug|Any CPU.Build.0 = Debug|Any CPU - {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Debug|x86.ActiveCfg = Debug|Any CPU - {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Debug|x86.Build.0 = Debug|Any CPU {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Release|Any CPU.ActiveCfg = Release|Any CPU {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Release|Any CPU.Build.0 = Release|Any CPU - {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Release|x86.ActiveCfg = Release|Any CPU - {1442B805-D6B1-4729-89F8-3A5A1C7547AD}.Release|x86.Build.0 = Release|Any CPU {3A413E59-A20E-477C-997E-64B1398E0E80}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {3A413E59-A20E-477C-997E-64B1398E0E80}.Debug|Any CPU.Build.0 = Debug|Any CPU - {3A413E59-A20E-477C-997E-64B1398E0E80}.Debug|x86.ActiveCfg = Debug|Any CPU - {3A413E59-A20E-477C-997E-64B1398E0E80}.Debug|x86.Build.0 = Debug|Any CPU {3A413E59-A20E-477C-997E-64B1398E0E80}.Release|Any CPU.ActiveCfg = Release|Any CPU {3A413E59-A20E-477C-997E-64B1398E0E80}.Release|Any CPU.Build.0 = Release|Any CPU - {3A413E59-A20E-477C-997E-64B1398E0E80}.Release|x86.ActiveCfg = Release|Any CPU - {3A413E59-A20E-477C-997E-64B1398E0E80}.Release|x86.Build.0 = Release|Any CPU {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Debug|x86.ActiveCfg = Debug|x86 - {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Debug|x86.Build.0 = Debug|x86 - {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Debug|x86.Deploy.0 = Debug|x86 {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Release|Any CPU.ActiveCfg = Release|Any CPU - {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Release|x86.ActiveCfg = Release|x86 - {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Release|x86.Build.0 = Release|x86 - {AADFFE7F-44CE-4FCA-BDB1-17C3F7020DCD}.Release|x86.Deploy.0 = Release|x86 {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Debug|Any CPU.Build.0 = Debug|Any CPU - {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Debug|x86.ActiveCfg = Debug|Any CPU - {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Debug|x86.Build.0 = Debug|Any CPU {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Release|Any CPU.ActiveCfg = Release|Any CPU {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Release|Any CPU.Build.0 = Release|Any CPU - {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Release|x86.ActiveCfg = Release|Any CPU - {D773ACCD-9C2D-4E94-A967-FAA7EA2D21CB}.Release|x86.Build.0 = Release|Any CPU {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Debug|x86.ActiveCfg = Debug|Any CPU - {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Debug|x86.Build.0 = Debug|Any CPU + {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Debug|Any CPU.Build.0 = Debug|Any CPU {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Release|Any CPU.ActiveCfg = Release|Any CPU - {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Release|x86.ActiveCfg = Release|Any CPU - {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Release|x86.Build.0 = Release|Any CPU - {9BA6FC55-148D-4481-B9E6-B31A1D4BCD0F}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {9BA6FC55-148D-4481-B9E6-B31A1D4BCD0F}.Debug|x86.ActiveCfg = Debug|Any CPU - {9BA6FC55-148D-4481-B9E6-B31A1D4BCD0F}.Release|Any CPU.ActiveCfg = Release|Any CPU - {9BA6FC55-148D-4481-B9E6-B31A1D4BCD0F}.Release|x86.ActiveCfg = Release|Any CPU + {EECDFE74-6CDC-45E0-AA39-34FF55FFB49F}.Release|Any CPU.Build.0 = Release|Any CPU {DFCB0240-50CF-4F56-92C7-05941569231D}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {DFCB0240-50CF-4F56-92C7-05941569231D}.Debug|Any CPU.Build.0 = Debug|Any CPU - {DFCB0240-50CF-4F56-92C7-05941569231D}.Debug|x86.ActiveCfg = Debug|Any CPU - {DFCB0240-50CF-4F56-92C7-05941569231D}.Debug|x86.Build.0 = Debug|Any CPU {DFCB0240-50CF-4F56-92C7-05941569231D}.Release|Any CPU.ActiveCfg = Release|Any CPU {DFCB0240-50CF-4F56-92C7-05941569231D}.Release|Any CPU.Build.0 = Release|Any CPU - {DFCB0240-50CF-4F56-92C7-05941569231D}.Release|x86.ActiveCfg = Release|Any CPU - {DFCB0240-50CF-4F56-92C7-05941569231D}.Release|x86.Build.0 = Release|Any CPU {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Debug|Any CPU.Build.0 = Debug|Any CPU - {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Debug|x86.ActiveCfg = Debug|Any CPU - {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Debug|x86.Build.0 = Debug|Any CPU {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Release|Any CPU.ActiveCfg = Release|Any CPU {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Release|Any CPU.Build.0 = Release|Any CPU - {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Release|x86.ActiveCfg = Release|Any CPU - {183631BD-EC15-47AD-9ABE-CD8DB748C066}.Release|x86.Build.0 = Release|Any CPU {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Debug|Any CPU.Build.0 = Debug|Any CPU - {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Debug|x86.ActiveCfg = Debug|Any CPU - {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Debug|x86.Build.0 = Debug|Any CPU {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Release|Any CPU.ActiveCfg = Release|Any CPU {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Release|Any CPU.Build.0 = Release|Any CPU - {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Release|x86.ActiveCfg = Release|Any CPU - {1117EFD6-3A46-47F7-9BEB-02792D213B8D}.Release|x86.Build.0 = Release|Any CPU {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Debug|Any CPU.Build.0 = Debug|Any CPU - {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Debug|x86.ActiveCfg = Debug|Any CPU - {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Debug|x86.Build.0 = Debug|Any CPU {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Release|Any CPU.ActiveCfg = Release|Any CPU {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Release|Any CPU.Build.0 = Release|Any CPU - {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Release|x86.ActiveCfg = Release|Any CPU - {E634EFE6-FEA0-4BB9-A7B9-D8809C33BCC8}.Release|x86.Build.0 = Release|Any CPU {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Debug|Any CPU.Build.0 = Debug|Any CPU - {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Debug|x86.ActiveCfg = Debug|Any CPU - {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Debug|x86.Build.0 = Debug|Any CPU {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Release|Any CPU.ActiveCfg = Release|Any CPU {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Release|Any CPU.Build.0 = Release|Any CPU - {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Release|x86.ActiveCfg = Release|Any CPU - {FD4D2994-9BEA-41A1-8C51-2E02D1E8503E}.Release|x86.Build.0 = Release|Any CPU {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Debug|x86.ActiveCfg = Debug|Any CPU - {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Debug|x86.Build.0 = Debug|Any CPU {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Release|Any CPU.ActiveCfg = Release|Any CPU {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Release|Any CPU.Build.0 = Release|Any CPU - {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Release|x86.ActiveCfg = Release|Any CPU - {B8C24868-6811-4FED-82DF-0C8CB607B00F}.Release|x86.Build.0 = Release|Any CPU {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Debug|Any CPU.Build.0 = Debug|Any CPU - {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Debug|x86.ActiveCfg = Debug|Any CPU - {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Debug|x86.Build.0 = Debug|Any CPU {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Release|Any CPU.ActiveCfg = Release|Any CPU {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Release|Any CPU.Build.0 = Release|Any CPU - {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Release|x86.ActiveCfg = Release|Any CPU - {DF86AFC2-CA79-4137-9BB5-70AA529C3B79}.Release|x86.Build.0 = Release|Any CPU {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Debug|Any CPU.Build.0 = Debug|Any CPU - {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Debug|x86.ActiveCfg = Debug|Any CPU - {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Debug|x86.Build.0 = Debug|Any CPU {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Release|Any CPU.ActiveCfg = Release|Any CPU {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Release|Any CPU.Build.0 = Release|Any CPU - {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Release|x86.ActiveCfg = Release|Any CPU - {6974D22C-EDE6-4BB2-AAD2-FF23ED6EC165}.Release|x86.Build.0 = Release|Any CPU {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Debug|Any CPU.Build.0 = Debug|Any CPU - {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Debug|x86.ActiveCfg = Debug|Any CPU - {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Debug|x86.Build.0 = Debug|Any CPU {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Release|Any CPU.ActiveCfg = Release|Any CPU {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Release|Any CPU.Build.0 = Release|Any CPU - {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Release|x86.ActiveCfg = Release|Any CPU - {A0B60830-D1C0-4E1F-9E44-793A71C5D720}.Release|x86.Build.0 = Release|Any CPU {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Debug|Any CPU.Build.0 = Debug|Any CPU - {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Debug|x86.ActiveCfg = Debug|Any CPU - {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Debug|x86.Build.0 = Debug|Any CPU {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Release|Any CPU.ActiveCfg = Release|Any CPU {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Release|Any CPU.Build.0 = Release|Any CPU - {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Release|x86.ActiveCfg = Release|Any CPU - {3D787D5F-1DCA-4C2E-8D3A-93353E7BB62A}.Release|x86.Build.0 = Release|Any CPU {CBB78367-91B7-4D53-AD31-429B71F867D2}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {CBB78367-91B7-4D53-AD31-429B71F867D2}.Debug|Any CPU.Build.0 = Debug|Any CPU - {CBB78367-91B7-4D53-AD31-429B71F867D2}.Debug|x86.ActiveCfg = Debug|Any CPU - {CBB78367-91B7-4D53-AD31-429B71F867D2}.Debug|x86.Build.0 = Debug|Any CPU {CBB78367-91B7-4D53-AD31-429B71F867D2}.Release|Any CPU.ActiveCfg = Release|Any CPU {CBB78367-91B7-4D53-AD31-429B71F867D2}.Release|Any CPU.Build.0 = Release|Any CPU - {CBB78367-91B7-4D53-AD31-429B71F867D2}.Release|x86.ActiveCfg = Release|Any CPU - {CBB78367-91B7-4D53-AD31-429B71F867D2}.Release|x86.Build.0 = Release|Any CPU {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Debug|Any CPU.Build.0 = Debug|Any CPU - {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Debug|x86.ActiveCfg = Debug|Any CPU - {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Debug|x86.Build.0 = Debug|Any CPU {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Release|Any CPU.ActiveCfg = Release|Any CPU {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Release|Any CPU.Build.0 = Release|Any CPU - {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Release|x86.ActiveCfg = Release|Any CPU - {DC7BAD19-540A-4407-8E89-C15C899D74DF}.Release|x86.Build.0 = Release|Any CPU {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Debug|Any CPU.Build.0 = Debug|Any CPU - {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Debug|x86.ActiveCfg = Debug|Any CPU - {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Debug|x86.Build.0 = Debug|Any CPU {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Release|Any CPU.ActiveCfg = Release|Any CPU {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Release|Any CPU.Build.0 = Release|Any CPU - {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Release|x86.ActiveCfg = Release|Any CPU - {E4902330-74FE-45F6-86C3-0A5F73A1EEC0}.Release|x86.Build.0 = Release|Any CPU {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Debug|Any CPU.Build.0 = Debug|Any CPU - {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Debug|x86.ActiveCfg = Debug|Any CPU - {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Debug|x86.Build.0 = Debug|Any CPU {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Release|Any CPU.ActiveCfg = Release|Any CPU {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Release|Any CPU.Build.0 = Release|Any CPU - {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Release|x86.ActiveCfg = Release|Any CPU - {637A5D55-908E-4AEE-B061-3981B66F1B9F}.Release|x86.Build.0 = Release|Any CPU {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Debug|Any CPU.Build.0 = Debug|Any CPU - {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Debug|x86.ActiveCfg = Debug|Any CPU - {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Debug|x86.Build.0 = Debug|Any CPU {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Release|Any CPU.ActiveCfg = Release|Any CPU {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Release|Any CPU.Build.0 = Release|Any CPU - {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Release|x86.ActiveCfg = Release|Any CPU - {3566E9FD-591D-4E42-BA38-11DBE2F13E82}.Release|x86.Build.0 = Release|Any CPU {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Debug|Any CPU.Build.0 = Debug|Any CPU - {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Debug|x86.ActiveCfg = Debug|Any CPU - {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Debug|x86.Build.0 = Debug|Any CPU {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Release|Any CPU.ActiveCfg = Release|Any CPU {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Release|Any CPU.Build.0 = Release|Any CPU - {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Release|x86.ActiveCfg = Release|Any CPU - {563D7C2E-14E2-47EC-95E4-4EA0BBA75C18}.Release|x86.Build.0 = Release|Any CPU {B66F428C-0419-438F-9303-C20A5E925257}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {B66F428C-0419-438F-9303-C20A5E925257}.Debug|Any CPU.Build.0 = Debug|Any CPU - {B66F428C-0419-438F-9303-C20A5E925257}.Debug|x86.ActiveCfg = Debug|Any CPU - {B66F428C-0419-438F-9303-C20A5E925257}.Debug|x86.Build.0 = Debug|Any CPU {B66F428C-0419-438F-9303-C20A5E925257}.Release|Any CPU.ActiveCfg = Release|Any CPU {B66F428C-0419-438F-9303-C20A5E925257}.Release|Any CPU.Build.0 = Release|Any CPU - {B66F428C-0419-438F-9303-C20A5E925257}.Release|x86.ActiveCfg = Release|Any CPU - {B66F428C-0419-438F-9303-C20A5E925257}.Release|x86.Build.0 = Release|Any CPU {E51283DC-7090-479E-B723-01C0953F18EA}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {E51283DC-7090-479E-B723-01C0953F18EA}.Debug|Any CPU.Build.0 = Debug|Any CPU - {E51283DC-7090-479E-B723-01C0953F18EA}.Debug|x86.ActiveCfg = Debug|Any CPU - {E51283DC-7090-479E-B723-01C0953F18EA}.Debug|x86.Build.0 = Debug|Any CPU {E51283DC-7090-479E-B723-01C0953F18EA}.Release|Any CPU.ActiveCfg = Release|Any CPU {E51283DC-7090-479E-B723-01C0953F18EA}.Release|Any CPU.Build.0 = Release|Any CPU - {E51283DC-7090-479E-B723-01C0953F18EA}.Release|x86.ActiveCfg = Release|Any CPU - {E51283DC-7090-479E-B723-01C0953F18EA}.Release|x86.Build.0 = Release|Any CPU {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Debug|Any CPU.Build.0 = Debug|Any CPU - {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Debug|x86.ActiveCfg = Debug|Any CPU - {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Debug|x86.Build.0 = Debug|Any CPU {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Release|Any CPU.ActiveCfg = Release|Any CPU {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Release|Any CPU.Build.0 = Release|Any CPU - {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Release|x86.ActiveCfg = Release|Any CPU - {A157AD69-59D4-49DE-94B3-DB883B2BEAA5}.Release|x86.Build.0 = Release|Any CPU {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Debug|Any CPU.Build.0 = Debug|Any CPU - {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Debug|x86.ActiveCfg = Debug|Any CPU - {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Debug|x86.Build.0 = Debug|Any CPU {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Release|Any CPU.ActiveCfg = Release|Any CPU {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Release|Any CPU.Build.0 = Release|Any CPU - {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Release|x86.ActiveCfg = Release|Any CPU - {CA8C83FC-FCDC-4F8F-9384-A2C9C5B2F7DD}.Release|x86.Build.0 = Release|Any CPU {9A702625-FB81-4400-ADAC-053553109F64}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {9A702625-FB81-4400-ADAC-053553109F64}.Debug|Any CPU.Build.0 = Debug|Any CPU - {9A702625-FB81-4400-ADAC-053553109F64}.Debug|x86.ActiveCfg = Debug|Any CPU - {9A702625-FB81-4400-ADAC-053553109F64}.Debug|x86.Build.0 = Debug|Any CPU {9A702625-FB81-4400-ADAC-053553109F64}.Release|Any CPU.ActiveCfg = Release|Any CPU {9A702625-FB81-4400-ADAC-053553109F64}.Release|Any CPU.Build.0 = Release|Any CPU - {9A702625-FB81-4400-ADAC-053553109F64}.Release|x86.ActiveCfg = Release|Any CPU - {9A702625-FB81-4400-ADAC-053553109F64}.Release|x86.Build.0 = Release|Any CPU {FB690197-2695-489C-A47C-439FF3AEF7A8}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {FB690197-2695-489C-A47C-439FF3AEF7A8}.Debug|x86.ActiveCfg = Debug|Any CPU - {FB690197-2695-489C-A47C-439FF3AEF7A8}.Debug|x86.Build.0 = Debug|Any CPU {FB690197-2695-489C-A47C-439FF3AEF7A8}.Release|Any CPU.ActiveCfg = Release|Any CPU - {FB690197-2695-489C-A47C-439FF3AEF7A8}.Release|x86.ActiveCfg = Release|Any CPU - {FB690197-2695-489C-A47C-439FF3AEF7A8}.Release|x86.Build.0 = Release|Any CPU {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Debug|x86.ActiveCfg = Debug|Any CPU - {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Debug|x86.Build.0 = Debug|Any CPU + {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Debug|Any CPU.Build.0 = Debug|Any CPU {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Release|Any CPU.ActiveCfg = Release|Any CPU - {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Release|x86.ActiveCfg = Release|Any CPU - {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Release|x86.Build.0 = Release|Any CPU + {6609C54A-71B9-4349-8E79-1DF3293BC7D0}.Release|Any CPU.Build.0 = Release|Any CPU {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Debug|Any CPU.Build.0 = Debug|Any CPU - {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Debug|x86.ActiveCfg = Debug|Any CPU - {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Debug|x86.Build.0 = Debug|Any CPU {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Release|Any CPU.ActiveCfg = Release|Any CPU {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Release|Any CPU.Build.0 = Release|Any CPU - {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Release|x86.ActiveCfg = Release|Any CPU - {63F10356-A09B-46B0-9AFA-FAB8326A52DD}.Release|x86.Build.0 = Release|Any CPU {DED183CA-5591-4CE5-A89D-987035BAC553}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {DED183CA-5591-4CE5-A89D-987035BAC553}.Debug|Any CPU.Build.0 = Debug|Any CPU - {DED183CA-5591-4CE5-A89D-987035BAC553}.Debug|x86.ActiveCfg = Debug|Any CPU - {DED183CA-5591-4CE5-A89D-987035BAC553}.Debug|x86.Build.0 = Debug|Any CPU {DED183CA-5591-4CE5-A89D-987035BAC553}.Release|Any CPU.ActiveCfg = Release|Any CPU {DED183CA-5591-4CE5-A89D-987035BAC553}.Release|Any CPU.Build.0 = Release|Any CPU - {DED183CA-5591-4CE5-A89D-987035BAC553}.Release|x86.ActiveCfg = Release|Any CPU - {DED183CA-5591-4CE5-A89D-987035BAC553}.Release|x86.Build.0 = Release|Any CPU {FBE658B3-684D-46E6-8668-50DEF0778538}.Debug|Any CPU.ActiveCfg = Debug|Any CPU {FBE658B3-684D-46E6-8668-50DEF0778538}.Debug|Any CPU.Build.0 = Debug|Any CPU - {FBE658B3-684D-46E6-8668-50DEF0778538}.Debug|x86.ActiveCfg = Debug|Any CPU - {FBE658B3-684D-46E6-8668-50DEF0778538}.Debug|x86.Build.0 = Debug|Any CPU {FBE658B3-684D-46E6-8668-50DEF0778538}.Release|Any CPU.ActiveCfg = Release|Any CPU {FBE658B3-684D-46E6-8668-50DEF0778538}.Release|Any CPU.Build.0 = Release|Any CPU - {FBE658B3-684D-46E6-8668-50DEF0778538}.Release|x86.ActiveCfg = Release|Any CPU - {FBE658B3-684D-46E6-8668-50DEF0778538}.Release|x86.Build.0 = Release|Any CPU - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Debug|Any CPU.ActiveCfg = Debug|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Debug|Any CPU.Build.0 = Debug|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Debug|x86.ActiveCfg = Debug|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Debug|x86.Build.0 = Debug|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Release|Any CPU.ActiveCfg = Release|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Release|Any CPU.Build.0 = Release|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Release|x86.ActiveCfg = Release|x86 - {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Release|x86.Build.0 = Release|x86 + {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Debug|Any CPU.ActiveCfg = Debug|Any CPU + {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Debug|Any CPU.Build.0 = Debug|Any CPU + {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Release|Any CPU.ActiveCfg = Release|Any CPU + {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107}.Release|Any CPU.Build.0 = Release|Any CPU {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Debug|Any CPU.ActiveCfg = Debug|Any CPU - {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Debug|Any CPU.Build.0 = Debug|Any CPU - {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Debug|x86.ActiveCfg = Debug|Any CPU - {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Debug|x86.Build.0 = Debug|Any CPU {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Release|Any CPU.ActiveCfg = Release|Any CPU - {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Release|Any CPU.Build.0 = Release|Any CPU - {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Release|x86.ActiveCfg = Release|Any CPU - {0B99EBF2-B964-4AAC-9EC5-76353610AAAE}.Release|x86.Build.0 = Release|Any CPU EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE @@ -978,60 +639,6 @@ Global {AF81C41B-06E6-4CA5-9FD4-A4E7042F1107} = {7E264F12-9EC3-4CDC-A187-6879C2B2BFCF} EndGlobalSection GlobalSection(ExtensibilityGlobals) = postSolution - SolutionGuid = {F7AF94B5-83B0-46CD-B258-67F2404F82FC} - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(Performance) = preSolution - HasPerformanceSessions = true - EndGlobalSection - GlobalSection(MonoDevelopProperties) = preSolution - StartupItem = MissionPlanner.csproj + SolutionGuid = {FD2C9507-1A09-4F5B-98AB-B6B194A4B260} EndGlobalSection EndGlobal diff --git a/MissionPlannerLib.csproj b/MissionPlannerLib.csproj index d03f4109fc..6eac41a5d0 100644 --- a/MissionPlannerLib.csproj +++ b/MissionPlannerLib.csproj @@ -471,6 +471,11 @@ + + + + + @@ -545,7 +550,6 @@ - diff --git a/Plugins/example18-externalapi.cs b/Plugins/example18-externalapi.cs index c9d688efa6..b3d1f2961f 100644 --- a/Plugins/example18-externalapi.cs +++ b/Plugins/example18-externalapi.cs @@ -1,317 +1,317 @@ -using MissionPlanner.Controls; -using MissionPlanner.Utilities; -using Org.BouncyCastle.Tls; -using Org.BouncyCastle.Tls.Crypto.Impl.BC; -using System; -using System.Collections.Generic; -using System.IO; -using System.Net; -using System.Net.Sockets; -using System.Threading; -using System.Threading.Tasks; -using System.Windows.Forms; -using Org.BouncyCastle.Utilities.Encoders; - -//loadassembly: BouncyCastle - -namespace MissionPlanner.plugins -{ - public class example18_externalapi : Plugin.Plugin - { - public override string Name { get; } = "External API"; - - public override string Version { get; } - - public override string Author { get; } - - public override bool Exit() - { - return true; - } - - public string address = Settings.Instance.GetString("ex_api_address", "droneshare.cubepilot.org"); - public int port = Settings.Instance.GetInt32("ex_api_port", 8042); - - public override bool Init() - { - var rootbut = new ToolStripMenuItem("Share to API"); - rootbut.Click += but_Click; - ToolStripItemCollection col = Host.FDMenuMap.Items; - col.Add(rootbut); - - return true; - } - - private void but_Click(object sender2, EventArgs e) - { - if (InputBox.Show("Server", "Server", ref address) != DialogResult.OK) - return; - if (InputBox.Show("Server port", "Server port", ref port) != DialogResult.OK) - return; - - string username = Settings.Instance.GetString("ex_api_username"); - string token = Settings.Instance.GetString("ex_api_psk"); - - if (InputBox.Show("Username", "Username", ref username) != DialogResult.OK) - return; - if (InputBox.Show("Token", "Token", ref token) != DialogResult.OK) - return; - - Settings.Instance["ex_api_address"] = address; - Settings.Instance["ex_api_port"] = port.ToString(); - - Settings.Instance["ex_api_username"] = username; - Settings.Instance["ex_api_psk"] = token; - - var psk = new BasicTlsPskIdentity(username, token.MakeBytes()); - var pskclient = new DTLSPsk(psk); - - Task.Run(() => - { - try - { - - - DtlsClientProtocol client = new DtlsClientProtocol(); - DatagramTransport transport = new UDPTransport(address, port); - var dtlstx = client.Connect(pskclient, transport); - - MainV2.comPort.OnPacketReceived += (sender, message) => - { - try - { - dtlstx.Send(message.buffer, 0, message.buffer.Length); - } - catch (Exception ex) - { - } - }; - - var buf = new byte[dtlstx.GetReceiveLimit()]; - - while (MainV2.comPort.BaseStream.IsOpen) - { - try - { - var read = dtlstx.Receive(buf, 0, buf.Length, 1000); - lock (MainV2.comPort.writelock) - { - if (MainV2.comPort.BaseStream.IsOpen) - MainV2.comPort.BaseStream.Write(buf, 0, read); - } - } - catch (Exception ex) - { - } - } - } - catch (Exception ex) - { - CustomMessageBox.Show(Strings.ERROR, ex.ToString()); - } - }); - } - - public override bool Loaded() - { - return true; - } - } - - internal class DTLSPsk : PskTlsClient - { - public DTLSPsk(TlsPskIdentity pskIdentity) : base(new BcTlsCrypto(new Org.BouncyCastle.Security.SecureRandom()), - pskIdentity) - { - } - - public override int[] GetCipherSuites() - { - return new int[] - { - CipherSuite.TLS_ECDHE_PSK_WITH_CHACHA20_POLY1305_SHA256, - CipherSuite.TLS_ECDHE_PSK_WITH_AES_128_CBC_SHA256, - CipherSuite.TLS_ECDHE_PSK_WITH_AES_128_CBC_SHA, - CipherSuite.TLS_DHE_PSK_WITH_CHACHA20_POLY1305_SHA256, - CipherSuite.TLS_DHE_PSK_WITH_AES_128_GCM_SHA256, - CipherSuite.TLS_DHE_PSK_WITH_AES_128_CBC_SHA256, - CipherSuite.TLS_DHE_PSK_WITH_AES_128_CBC_SHA, - CipherSuite.TLS_PSK_WITH_AES_128_GCM_SHA256 - }; - } - - public override void NotifyAlertRaised(short alertLevel, short alertDescription, string message, - Exception cause) - { - TextWriter output = (alertLevel == AlertLevel.fatal) ? Console.Error : Console.Out; - output.WriteLine("DTLS client raised alert: " + AlertLevel.GetText(alertLevel) - + ", " + AlertDescription.GetText(alertDescription)); - if (message != null) - { - output.WriteLine("> " + message); - } - - if (cause != null) - { - output.WriteLine(cause); - } - } - - public override void NotifyAlertReceived(short alertLevel, short alertDescription) - { - TextWriter output = (alertLevel == AlertLevel.fatal) ? Console.Error : Console.Out; - output.WriteLine("DTLS client received alert: " + AlertLevel.GetText(alertLevel) - + ", " + AlertDescription.GetText(alertDescription)); - } - - public override void NotifyServerVersion(ProtocolVersion serverVersion) - { - base.NotifyServerVersion(serverVersion); - - Console.WriteLine("DTLS client negotiated " + serverVersion); - } - - public override TlsAuthentication GetAuthentication() - { - return base.GetAuthentication(); - } - - public override void NotifySecureRenegotiation(bool secureRenegotiation) - { - // this is psk, not needed - //base.NotifySecureRenegotiation(secureRenegotiation); - } - - public override void NotifyHandshakeComplete() - { - base.NotifyHandshakeComplete(); - - ProtocolName protocolName = m_context.SecurityParameters.ApplicationProtocol; - if (protocolName != null) - { - Console.WriteLine("Client ALPN: " + protocolName.GetUtf8Decoding()); - } - - TlsSession newSession = m_context.Session; - if (newSession != null) - { - if (newSession.IsResumable) - { - byte[] newSessionID = newSession.SessionID; - string hex = ToHexString(newSessionID); - /* - if (base.m_session != null && Arrays.AreEqual(base.m_session.SessionID, newSessionID)) - { - Console.WriteLine("Client resumed session: " + hex); - } - else - { - Console.WriteLine("Client established session: " + hex); - } - - this.m_session = newSession; - */ - - Console.WriteLine("Client established session: " + hex); - } - - byte[] tlsServerEndPoint = m_context.ExportChannelBinding(ChannelBinding.tls_server_end_point); - if (null != tlsServerEndPoint) - { - Console.WriteLine("Client 'tls-server-end-point': " + ToHexString(tlsServerEndPoint)); - } - - byte[] tlsUnique = m_context.ExportChannelBinding(ChannelBinding.tls_unique); - Console.WriteLine("Client 'tls-unique': " + ToHexString(tlsUnique)); - } - } - - public override IDictionary GetClientExtensions() - { - if (m_context.SecurityParameters.ClientRandom == null) - throw new TlsFatalAlert(AlertDescription.internal_error); - - return base.GetClientExtensions(); - } - - public override void ProcessServerExtensions(IDictionary serverExtensions) - { - if (m_context.SecurityParameters.ServerRandom == null) - throw new TlsFatalAlert(AlertDescription.internal_error); - - base.ProcessServerExtensions(serverExtensions); - } - - protected virtual string ToHexString(byte[] data) - { - return data == null ? "(null)" : Hex.ToHexString(data); - } - - protected override ProtocolVersion[] GetSupportedVersions() - { - return ProtocolVersion.DTLSv12.Only(); - } - } - - public class UDPTransport : DatagramTransport - { - private string address; - private int port; - private UdpClient _udpclient; - - private readonly ByteQueue mRecordQueue = new ByteQueue(); - - public UDPTransport(string address, int port) - { - this.address = address; - this.port = port; - - _udpclient = new UdpClient(address, port); - } - - public void Close() - { - _udpclient.Close(); - } - - public int GetReceiveLimit() - { - return 1 << 14; - } - - public int GetSendLimit() - { - return 1 << 14; - } - - public int Receive(byte[] buf, int off, int len, int waitMillis) - { - var endtime = DateTime.Now.AddMilliseconds(waitMillis); - while (mRecordQueue.Available < len && endtime > DateTime.Now) - { - if (_udpclient.Available > 0) - { - IPEndPoint ep = null; - var data = _udpclient.Receive(ref ep); - - mRecordQueue.AddData(data, 0, data.Length); - - break; - } - - Thread.Yield(); - } - - len = Math.Min(mRecordQueue.Available, len); - mRecordQueue.Read(buf, off, len, 0); - mRecordQueue.RemoveData(len); - return len; - } - - public void Send(byte[] buf, int off, int len) - { - var span = new ReadOnlySpan(buf, off, len); - _udpclient.Send(span.ToArray(), span.Length); - } - } +using MissionPlanner.Controls; +using MissionPlanner.Utilities; +using Org.BouncyCastle.Tls; +using Org.BouncyCastle.Tls.Crypto.Impl.BC; +using System; +using System.Collections.Generic; +using System.IO; +using System.Net; +using System.Net.Sockets; +using System.Threading; +using System.Threading.Tasks; +using System.Windows.Forms; +using Org.BouncyCastle.Utilities.Encoders; + +//loadassembly: BouncyCastle.Cryptography + +namespace MissionPlanner.plugins +{ + public class example18_externalapi : Plugin.Plugin + { + public override string Name { get; } = "External API"; + + public override string Version { get; } + + public override string Author { get; } + + public override bool Exit() + { + return true; + } + + public string address = Settings.Instance.GetString("ex_api_address", "droneshare.cubepilot.org"); + public int port = Settings.Instance.GetInt32("ex_api_port", 8042); + + public override bool Init() + { + var rootbut = new ToolStripMenuItem("Share to API"); + rootbut.Click += but_Click; + ToolStripItemCollection col = Host.FDMenuMap.Items; + col.Add(rootbut); + + return true; + } + + private void but_Click(object sender2, EventArgs e) + { + if (InputBox.Show("Server", "Server", ref address) != DialogResult.OK) + return; + if (InputBox.Show("Server port", "Server port", ref port) != DialogResult.OK) + return; + + string username = Settings.Instance.GetString("ex_api_username"); + string token = Settings.Instance.GetString("ex_api_psk"); + + if (InputBox.Show("Username", "Username", ref username) != DialogResult.OK) + return; + if (InputBox.Show("Token", "Token", ref token) != DialogResult.OK) + return; + + Settings.Instance["ex_api_address"] = address; + Settings.Instance["ex_api_port"] = port.ToString(); + + Settings.Instance["ex_api_username"] = username; + Settings.Instance["ex_api_psk"] = token; + + var psk = new BasicTlsPskIdentity(username, token.MakeBytes()); + var pskclient = new DTLSPsk(psk); + + Task.Run(() => + { + try + { + + + DtlsClientProtocol client = new DtlsClientProtocol(); + DatagramTransport transport = new UDPTransport(address, port); + var dtlstx = client.Connect(pskclient, transport); + + MainV2.comPort.OnPacketReceived += (sender, message) => + { + try + { + dtlstx.Send(message.buffer, 0, message.buffer.Length); + } + catch (Exception ex) + { + } + }; + + var buf = new byte[dtlstx.GetReceiveLimit()]; + + while (MainV2.comPort.BaseStream.IsOpen) + { + try + { + var read = dtlstx.Receive(buf, 0, buf.Length, 1000); + lock (MainV2.comPort.writelock) + { + if (MainV2.comPort.BaseStream.IsOpen) + MainV2.comPort.BaseStream.Write(buf, 0, read); + } + } + catch (Exception ex) + { + } + } + } + catch (Exception ex) + { + CustomMessageBox.Show(Strings.ERROR, ex.ToString()); + } + }); + } + + public override bool Loaded() + { + return true; + } + } + + internal class DTLSPsk : PskTlsClient + { + public DTLSPsk(TlsPskIdentity pskIdentity) : base(new BcTlsCrypto(new Org.BouncyCastle.Security.SecureRandom()), + pskIdentity) + { + } + + public override int[] GetCipherSuites() + { + return new int[] + { + CipherSuite.TLS_ECDHE_PSK_WITH_CHACHA20_POLY1305_SHA256, + CipherSuite.TLS_ECDHE_PSK_WITH_AES_128_CBC_SHA256, + CipherSuite.TLS_ECDHE_PSK_WITH_AES_128_CBC_SHA, + CipherSuite.TLS_DHE_PSK_WITH_CHACHA20_POLY1305_SHA256, + CipherSuite.TLS_DHE_PSK_WITH_AES_128_GCM_SHA256, + CipherSuite.TLS_DHE_PSK_WITH_AES_128_CBC_SHA256, + CipherSuite.TLS_DHE_PSK_WITH_AES_128_CBC_SHA, + CipherSuite.TLS_PSK_WITH_AES_128_GCM_SHA256 + }; + } + + public override void NotifyAlertRaised(short alertLevel, short alertDescription, string message, + Exception cause) + { + TextWriter output = (alertLevel == AlertLevel.fatal) ? Console.Error : Console.Out; + output.WriteLine("DTLS client raised alert: " + AlertLevel.GetText(alertLevel) + + ", " + AlertDescription.GetText(alertDescription)); + if (message != null) + { + output.WriteLine("> " + message); + } + + if (cause != null) + { + output.WriteLine(cause); + } + } + + public override void NotifyAlertReceived(short alertLevel, short alertDescription) + { + TextWriter output = (alertLevel == AlertLevel.fatal) ? Console.Error : Console.Out; + output.WriteLine("DTLS client received alert: " + AlertLevel.GetText(alertLevel) + + ", " + AlertDescription.GetText(alertDescription)); + } + + public override void NotifyServerVersion(ProtocolVersion serverVersion) + { + base.NotifyServerVersion(serverVersion); + + Console.WriteLine("DTLS client negotiated " + serverVersion); + } + + public override TlsAuthentication GetAuthentication() + { + return base.GetAuthentication(); + } + + public override void NotifySecureRenegotiation(bool secureRenegotiation) + { + // this is psk, not needed + //base.NotifySecureRenegotiation(secureRenegotiation); + } + + public override void NotifyHandshakeComplete() + { + base.NotifyHandshakeComplete(); + + ProtocolName protocolName = m_context.SecurityParameters.ApplicationProtocol; + if (protocolName != null) + { + Console.WriteLine("Client ALPN: " + protocolName.GetUtf8Decoding()); + } + + TlsSession newSession = m_context.Session; + if (newSession != null) + { + if (newSession.IsResumable) + { + byte[] newSessionID = newSession.SessionID; + string hex = ToHexString(newSessionID); + /* + if (base.m_session != null && Arrays.AreEqual(base.m_session.SessionID, newSessionID)) + { + Console.WriteLine("Client resumed session: " + hex); + } + else + { + Console.WriteLine("Client established session: " + hex); + } + + this.m_session = newSession; + */ + + Console.WriteLine("Client established session: " + hex); + } + + byte[] tlsServerEndPoint = m_context.ExportChannelBinding(ChannelBinding.tls_server_end_point); + if (null != tlsServerEndPoint) + { + Console.WriteLine("Client 'tls-server-end-point': " + ToHexString(tlsServerEndPoint)); + } + + byte[] tlsUnique = m_context.ExportChannelBinding(ChannelBinding.tls_unique); + Console.WriteLine("Client 'tls-unique': " + ToHexString(tlsUnique)); + } + } + + public override IDictionary GetClientExtensions() + { + if (m_context.SecurityParameters.ClientRandom == null) + throw new TlsFatalAlert(AlertDescription.internal_error); + + return base.GetClientExtensions(); + } + + public override void ProcessServerExtensions(IDictionary serverExtensions) + { + if (m_context.SecurityParameters.ServerRandom == null) + throw new TlsFatalAlert(AlertDescription.internal_error); + + base.ProcessServerExtensions(serverExtensions); + } + + protected virtual string ToHexString(byte[] data) + { + return data == null ? "(null)" : Hex.ToHexString(data); + } + + protected override ProtocolVersion[] GetSupportedVersions() + { + return ProtocolVersion.DTLSv12.Only(); + } + } + + public class UDPTransport : DatagramTransport + { + private string address; + private int port; + private UdpClient _udpclient; + + private readonly ByteQueue mRecordQueue = new ByteQueue(); + + public UDPTransport(string address, int port) + { + this.address = address; + this.port = port; + + _udpclient = new UdpClient(address, port); + } + + public void Close() + { + _udpclient.Close(); + } + + public int GetReceiveLimit() + { + return 1 << 14; + } + + public int GetSendLimit() + { + return 1 << 14; + } + + public int Receive(byte[] buf, int off, int len, int waitMillis) + { + var endtime = DateTime.Now.AddMilliseconds(waitMillis); + while (mRecordQueue.Available < len && endtime > DateTime.Now) + { + if (_udpclient.Available > 0) + { + IPEndPoint ep = null; + var data = _udpclient.Receive(ref ep); + + mRecordQueue.AddData(data, 0, data.Length); + + break; + } + + Thread.Yield(); + } + + len = Math.Min(mRecordQueue.Available, len); + mRecordQueue.Read(buf, off, len, 0); + mRecordQueue.RemoveData(len); + return len; + } + + public void Send(byte[] buf, int off, int len) + { + var span = new ReadOnlySpan(buf, off, len); + _udpclient.Send(span.ToArray(), span.Length); + } + } } \ No newline at end of file diff --git a/Radio/ComPort.cs b/Radio/ComPort.cs new file mode 100644 index 0000000000..043272b30a --- /dev/null +++ b/Radio/ComPort.cs @@ -0,0 +1,31 @@ +using System; +using MissionPlanner.Comms; + +namespace MissionPlanner.Radio +{ + public static class ComPort + { + static ICommsSerial _Port; + + public static ICommsSerial GetComPortForSiKRadio() + { + if (_Port == null) + { + MainV2.comPort.Close(); + MissionPlanner.Radio.Sikradio.Connect(ref _Port); + } + + return _Port; + } + + public static void FinishedWithComPortForSiKRadio() + { + if (_Port != null) + { + _Port.Dispose(); + _Port = null; + } + } + } + +} \ No newline at end of file diff --git a/Radio/Models.cs b/Radio/Models.cs index 9832f02390..eae4eda095 100644 --- a/Radio/Models.cs +++ b/Radio/Models.cs @@ -37,6 +37,7 @@ class ExtraParamControlsSet LabelComboBoxPair TXENCAP; LabelComboBoxPair RXENCAP; LabelComboBoxPair MAX_DATA; + LabelComboBoxPair MAX_RETRIES; IEnumerable Others; bool Remote; @@ -45,6 +46,7 @@ public ExtraParamControlsSet(Label lblNodeID, ComboBox cmbNodeID, Label lblTXENCAP, ComboBox cmbTXENCAP, Label lblRXENCAP, ComboBox cmbRXENCAP, Label lblMAX_DATA, ComboBox cmbMAX_DATA, + Label lblMAX_RETRIES, ComboBox cmbMAX_RETRIES, Control[] Others, bool Remote) { NodeID = new LabelComboBoxPair(lblNodeID, cmbNodeID); @@ -52,12 +54,25 @@ public ExtraParamControlsSet(Label lblNodeID, ComboBox cmbNodeID, TXENCAP = new LabelComboBoxPair(lblTXENCAP, cmbTXENCAP); RXENCAP = new LabelComboBoxPair(lblRXENCAP, cmbRXENCAP); MAX_DATA = new LabelComboBoxPair(lblMAX_DATA, cmbMAX_DATA); + MAX_RETRIES = new LabelComboBoxPair(lblMAX_RETRIES, cmbMAX_RETRIES); this.Others = Others; this.Remote = Remote; } - public void SetModel(Model M) + /// + /// Reconfigure the GUI for the given modem firmware type + /// + /// The modem firmware type. + /// The settings retrieved from the modem. Must not be null. + public void SetModel(Model M, Dictionary Settings) { + NodeID.Reset(); + DestID.Reset(); + TXENCAP.Reset(); + RXENCAP.Reset(); + MAX_DATA.Reset(); + MAX_RETRIES.Reset(); + string Prefix = Remote ? "R" : ""; switch (M) @@ -73,7 +88,7 @@ public void SetModel(Model M) RXENCAP.ComboBox.Name = Prefix + "NODECOUNT"; RXENCAP.Label.Text = "Node Count"; NodeID.ComboBox.DataSource = Sikradio.Range(0, 1, 29); - var Temp = (List)Sikradio.Range(0, 1, 29); + var Temp = new List(Sikradio.Range(0, 1, 29)); Temp.Add(65535); DestID.ComboBox.DataSource = Temp; TXENCAP.ComboBox.DataSource = Sikradio.Range(0, 1, 1); @@ -103,14 +118,27 @@ public void SetModel(Model M) case Model.MULTIPOINT_X: { DestID.ComboBox.Name = Prefix + "NODEDESTINATION"; - TXENCAP.ComboBox.Name = Prefix + "NODECOUNT"; - TXENCAP.Label.Text = "Node Count"; + if (Settings.ContainsKey("NETCOUNT")) + { + TXENCAP.ComboBox.Name = Prefix + "NETCOUNT"; + TXENCAP.Label.Text = "Net Count"; + } + else + { + TXENCAP.ComboBox.Name = Prefix + "NODECOUNT"; + TXENCAP.Label.Text = "Node Count"; + } RXENCAP.ComboBox.Name = Prefix + "SERBREAKMS10"; RXENCAP.Label.Text = "Ser. brk. x10ms"; - MAX_DATA.ComboBox.Name = "GPO1_3STATLED"; - MAX_DATA.Label.Text = "GPO1_\n3STATLED"; + if (Settings.ContainsKey("MASTERBACKUP")) + { + MAX_DATA.ComboBox.Name = Prefix + "MASTERBACKUP"; + MAX_DATA.Label.Text = "Master Bckp"; + } + MAX_RETRIES.ComboBox.Name = Prefix + "RXFRAME"; + MAX_RETRIES.Label.Text = "Rx Frame"; NodeID.ComboBox.DataSource = Sikradio.Range(0, 1, 29); - var Temp = (List)Sikradio.Range(0, 1, 29); + var Temp = new List(Sikradio.Range(0, 1, 29)); Temp.Add(65535); DestID.ComboBox.DataSource = Temp; TXENCAP.ComboBox.DataSource = Sikradio.Range(0, 1, 1); @@ -121,7 +149,14 @@ public void SetModel(Model M) DestID.Visible = true; TXENCAP.Visible = true; RXENCAP.Visible = true; - MAX_DATA.Visible = true; + if (Settings.ContainsKey("MASTERBACKUP")) + { + MAX_DATA.Visible = true; + } + if (Settings.ContainsKey("RXFRAME")) + { + MAX_RETRIES.Visible = true; + } } break; } @@ -134,6 +169,7 @@ void SetAllVisible(bool V) TXENCAP.Visible = V; RXENCAP.Visible = V; MAX_DATA.Visible = V; + MAX_RETRIES.Visible = V; foreach (var x in Others) { x.Visible = V; @@ -145,11 +181,15 @@ class LabelComboBoxPair { public readonly Label Label; public readonly ComboBox ComboBox; + public readonly string OrigName; + public readonly string OrigLabel; public LabelComboBoxPair(Label L, ComboBox C) { this.Label = L; this.ComboBox = C; + OrigName = C.Name; + OrigLabel = L.Text; } public bool Visible @@ -164,5 +204,11 @@ public bool Visible ComboBox.Visible = value; } } + + public void Reset() + { + Label.Text = OrigLabel; + ComboBox.Name = OrigName; + } } } \ No newline at end of file diff --git a/Radio/Sikradio.Designer.cs b/Radio/Sikradio.Designer.cs index cf06b1f7f4..c0a7ae9118 100644 --- a/Radio/Sikradio.Designer.cs +++ b/Radio/Sikradio.Designer.cs @@ -66,6 +66,16 @@ private void InitializeComponent() this.TXPOWER = new System.Windows.Forms.ComboBox(); this.ECC = new System.Windows.Forms.CheckBox(); this.OPPRESEND = new System.Windows.Forms.CheckBox(); + this.ENCRYPTION_LEVEL = new System.Windows.Forms.ComboBox(); + this.RENCRYPTION_LEVEL = new System.Windows.Forms.ComboBox(); + this.FSFRAMELOSS = new System.Windows.Forms.ComboBox(); + this.RFSFRAMELOSS = new System.Windows.Forms.ComboBox(); + this.GPO1_3SBUSIN = new System.Windows.Forms.CheckBox(); + this.RGPO1_3SBUSIN = new System.Windows.Forms.CheckBox(); + this.GPO1_3STATLED = new System.Windows.Forms.CheckBox(); + this.GPO1_0TXEN485 = new System.Windows.Forms.CheckBox(); + this.RGPO1_0TXEN485 = new System.Windows.Forms.CheckBox(); + this.RGPO1_3STATLED = new System.Windows.Forms.CheckBox(); this.RTI = new System.Windows.Forms.TextBox(); this.ATI = new System.Windows.Forms.TextBox(); this.label11 = new System.Windows.Forms.Label(); @@ -73,6 +83,22 @@ private void InitializeComponent() this.lbl_status = new System.Windows.Forms.Label(); this.ATI3 = new System.Windows.Forms.TextBox(); this.groupBoxLocal = new System.Windows.Forms.GroupBox(); + this.label54 = new System.Windows.Forms.Label(); + this.GPO1_3AUXOUT = new System.Windows.Forms.CheckBox(); + this.lblGPO1_3AUXOUT = new System.Windows.Forms.Label(); + this.GPI1_2AUXIN = new System.Windows.Forms.CheckBox(); + this.lblGPI1_2AUXIN = new System.Windows.Forms.Label(); + this.lblGPIO1_1FUNC = new System.Windows.Forms.Label(); + this.GPIO1_1FUNC = new System.Windows.Forms.ComboBox(); + this.lblGPO1_0TXEN485 = new System.Windows.Forms.Label(); + this.lblGPO1_3STATLED = new System.Windows.Forms.Label(); + this.GPO1_3SBUSOUT = new System.Windows.Forms.ComboBox(); + this.label49 = new System.Windows.Forms.Label(); + this.txtCountry = new System.Windows.Forms.TextBox(); + this.label45 = new System.Windows.Forms.Label(); + this.RATE_FREQBAND = new System.Windows.Forms.ComboBox(); + this.lblSBUSOUT = new System.Windows.Forms.Label(); + this.lblSBUSIN = new System.Windows.Forms.Label(); this.btnRandom = new System.Windows.Forms.Button(); this.lblRX_ENCAP_METHOD = new System.Windows.Forms.Label(); this.RX_ENCAP_METHOD = new System.Windows.Forms.ComboBox(); @@ -82,17 +108,17 @@ private void InitializeComponent() this.lblNODEID = new System.Windows.Forms.Label(); this.DESTID = new System.Windows.Forms.ComboBox(); this.NODEID = new System.Windows.Forms.ComboBox(); - this.label40 = new System.Windows.Forms.Label(); - this.label39 = new System.Windows.Forms.Label(); + this.lblGPO1_1R_COUT = new System.Windows.Forms.Label(); + this.lblGPI1_1R_CIN = new System.Windows.Forms.Label(); this.label2 = new System.Windows.Forms.Label(); this.label1 = new System.Windows.Forms.Label(); this.FORMAT = new System.Windows.Forms.TextBox(); this.label3 = new System.Windows.Forms.Label(); - this.label4 = new System.Windows.Forms.Label(); - this.label5 = new System.Windows.Forms.Label(); - this.label6 = new System.Windows.Forms.Label(); - this.label8 = new System.Windows.Forms.Label(); - this.label7 = new System.Windows.Forms.Label(); + this.lblNETID = new System.Windows.Forms.Label(); + this.lblTXPOWER = new System.Windows.Forms.Label(); + this.lblECC = new System.Windows.Forms.Label(); + this.lblOPPRESEND = new System.Windows.Forms.Label(); + this.lblMAVLINK = new System.Windows.Forms.Label(); this.lblANT_MODE = new System.Windows.Forms.Label(); this.ANT_MODE = new System.Windows.Forms.ComboBox(); this.lblSER_BRK_DETMS = new System.Windows.Forms.Label(); @@ -103,21 +129,36 @@ private void InitializeComponent() this.MAX_RETRIES = new System.Windows.Forms.ComboBox(); this.MAX_DATA = new System.Windows.Forms.ComboBox(); this.lblMAX_DATA = new System.Windows.Forms.Label(); - this.ENCRYPTION_LEVEL = new System.Windows.Forms.CheckBox(); - this.label36 = new System.Windows.Forms.Label(); + this.lblENCRYPTION_LEVEL = new System.Windows.Forms.Label(); this.label35 = new System.Windows.Forms.Label(); - this.txt_aeskey = new System.Windows.Forms.TextBox(); - this.label19 = new System.Windows.Forms.Label(); + this.AESKEY = new System.Windows.Forms.TextBox(); + this.lblRTSCTS = new System.Windows.Forms.Label(); this.linkLabel_mavlink = new System.Windows.Forms.LinkLabel(); this.linkLabel_lowlatency = new System.Windows.Forms.LinkLabel(); - this.label18 = new System.Windows.Forms.Label(); - this.label13 = new System.Windows.Forms.Label(); - this.label17 = new System.Windows.Forms.Label(); - this.label16 = new System.Windows.Forms.Label(); - this.label15 = new System.Windows.Forms.Label(); - this.label14 = new System.Windows.Forms.Label(); + this.lblMAX_WINDOW = new System.Windows.Forms.Label(); + this.lblMIN_FREQ = new System.Windows.Forms.Label(); + this.lblLBT_RSSI = new System.Windows.Forms.Label(); + this.lblDUTY_CYCLE = new System.Windows.Forms.Label(); + this.lblNUM_CHANNELS = new System.Windows.Forms.Label(); + this.lblMAX_FREQ = new System.Windows.Forms.Label(); this.ATI2 = new System.Windows.Forms.TextBox(); this.groupBoxRemote = new System.Windows.Forms.GroupBox(); + this.lblRFSFRAMELOSS = new System.Windows.Forms.Label(); + this.RGPO1_3AUXOUT = new System.Windows.Forms.CheckBox(); + this.lblRGPO1_3AUXOUT = new System.Windows.Forms.Label(); + this.RGPI1_2AUXIN = new System.Windows.Forms.CheckBox(); + this.lblRGPI1_2AUXIN = new System.Windows.Forms.Label(); + this.lblRGPIO1_1FUNC = new System.Windows.Forms.Label(); + this.RGPIO1_1FUNC = new System.Windows.Forms.ComboBox(); + this.lblRGPO1_0TXEN485 = new System.Windows.Forms.Label(); + this.lblRGPO1_3STATLED = new System.Windows.Forms.Label(); + this.RGPO1_3SBUSOUT = new System.Windows.Forms.ComboBox(); + this.label50 = new System.Windows.Forms.Label(); + this.txtRCountry = new System.Windows.Forms.TextBox(); + this.lblRSBUSOUT = new System.Windows.Forms.Label(); + this.lblRSBUSIN = new System.Windows.Forms.Label(); + this.label46 = new System.Windows.Forms.Label(); + this.RRATE_FREQBAND = new System.Windows.Forms.ComboBox(); this.lblRRX_ENCAP_METHOD = new System.Windows.Forms.Label(); this.RRX_ENCAP_METHOD = new System.Windows.Forms.ComboBox(); this.lblRTX_ENCAP_METHOD = new System.Windows.Forms.Label(); @@ -126,14 +167,14 @@ private void InitializeComponent() this.lblRNODEID = new System.Windows.Forms.Label(); this.RDESTID = new System.Windows.Forms.ComboBox(); this.RNODEID = new System.Windows.Forms.ComboBox(); - this.label41 = new System.Windows.Forms.Label(); + this.lblRGPO1_1R_COUT = new System.Windows.Forms.Label(); this.RFORMAT = new System.Windows.Forms.TextBox(); - this.label42 = new System.Windows.Forms.Label(); - this.label25 = new System.Windows.Forms.Label(); - this.label26 = new System.Windows.Forms.Label(); - this.label27 = new System.Windows.Forms.Label(); - this.label28 = new System.Windows.Forms.Label(); - this.label29 = new System.Windows.Forms.Label(); + this.lblRGPI1_1R_CIN = new System.Windows.Forms.Label(); + this.lblROPPRESEND = new System.Windows.Forms.Label(); + this.lblRMAVLINK = new System.Windows.Forms.Label(); + this.lblRECC = new System.Windows.Forms.Label(); + this.lblRTXPOWER = new System.Windows.Forms.Label(); + this.lblRNETID = new System.Windows.Forms.Label(); this.label32 = new System.Windows.Forms.Label(); this.label30 = new System.Windows.Forms.Label(); this.label31 = new System.Windows.Forms.Label(); @@ -148,26 +189,32 @@ private void InitializeComponent() this.RMAX_DATA = new System.Windows.Forms.ComboBox(); this.lblRMAX_DATA = new System.Windows.Forms.Label(); this.label38 = new System.Windows.Forms.Label(); - this.RENCRYPTION_LEVEL = new System.Windows.Forms.CheckBox(); - this.txt_Raeskey = new System.Windows.Forms.TextBox(); - this.label37 = new System.Windows.Forms.Label(); - this.label33 = new System.Windows.Forms.Label(); - this.label34 = new System.Windows.Forms.Label(); - this.label24 = new System.Windows.Forms.Label(); - this.label23 = new System.Windows.Forms.Label(); - this.label22 = new System.Windows.Forms.Label(); - this.label21 = new System.Windows.Forms.Label(); - this.label20 = new System.Windows.Forms.Label(); + this.RAESKEY = new System.Windows.Forms.TextBox(); + this.lblRENCRYPTION_LEVEL = new System.Windows.Forms.Label(); + this.lblRRTSCTS = new System.Windows.Forms.Label(); + this.lblRMAX_WINDOW = new System.Windows.Forms.Label(); + this.lblRMIN_FREQ = new System.Windows.Forms.Label(); + this.lblRMAX_FREQ = new System.Windows.Forms.Label(); + this.lblRNUM_CHANNELS = new System.Windows.Forms.Label(); + this.lblRDUTY_CYCLE = new System.Windows.Forms.Label(); + this.lblRLBT_RSSI = new System.Windows.Forms.Label(); this.RTI2 = new System.Windows.Forms.TextBox(); this.label9 = new System.Windows.Forms.Label(); this.label10 = new System.Windows.Forms.Label(); - this.BUT_SetPPMFailSafe = new MissionPlanner.Controls.MyButton(); + this.dlgSave = new System.Windows.Forms.SaveFileDialog(); + this.dlgOpen = new System.Windows.Forms.OpenFileDialog(); this.BUT_loadcustom = new MissionPlanner.Controls.MyButton(); this.BUT_resettodefault = new MissionPlanner.Controls.MyButton(); + this.btnRemoteLoadFromFile = new MissionPlanner.Controls.MyButton(); + this.btnRemoteSaveToFile = new MissionPlanner.Controls.MyButton(); + this.BUT_SetPPMFailSafeRemote = new MissionPlanner.Controls.MyButton(); + this.BUT_SetPPMFailSafe = new MissionPlanner.Controls.MyButton(); this.BUT_savesettings = new MissionPlanner.Controls.MyButton(); this.BUT_getcurrent = new MissionPlanner.Controls.MyButton(); this.BUT_upload = new MissionPlanner.Controls.MyButton(); this.BUT_Syncoptions = new MissionPlanner.Controls.MyButton(); + this.btnSaveToFile = new MissionPlanner.Controls.MyButton(); + this.btnLoadFromFile = new MissionPlanner.Controls.MyButton(); this.groupBoxLocal.SuspendLayout(); this.groupBoxRemote.SuspendLayout(); this.SuspendLayout(); @@ -237,7 +284,6 @@ private void InitializeComponent() resources.GetString("RMAX_WINDOW.Items29"), resources.GetString("RMAX_WINDOW.Items30")}); this.RMAX_WINDOW.Name = "RMAX_WINDOW"; - this.toolTip1.SetToolTip(this.RMAX_WINDOW, resources.GetString("RMAX_WINDOW.ToolTip")); // // RMAX_FREQ // @@ -344,7 +390,6 @@ private void InitializeComponent() resources.ApplyResources(this.RMAVLINK, "RMAVLINK"); this.RMAVLINK.FormattingEnabled = true; this.RMAVLINK.Name = "RMAVLINK"; - this.toolTip1.SetToolTip(this.RMAVLINK, resources.GetString("RMAVLINK.ToolTip")); // // RGPO1_1R_COUT // @@ -510,7 +555,6 @@ private void InitializeComponent() resources.GetString("MAX_WINDOW.Items29"), resources.GetString("MAX_WINDOW.Items30")}); this.MAX_WINDOW.Name = "MAX_WINDOW"; - this.toolTip1.SetToolTip(this.MAX_WINDOW, resources.GetString("MAX_WINDOW.ToolTip")); // // MAX_FREQ // @@ -742,6 +786,70 @@ private void InitializeComponent() this.OPPRESEND.Name = "OPPRESEND"; this.toolTip1.SetToolTip(this.OPPRESEND, resources.GetString("OPPRESEND.ToolTip")); // + // ENCRYPTION_LEVEL + // + this.ENCRYPTION_LEVEL.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.ENCRYPTION_LEVEL, "ENCRYPTION_LEVEL"); + this.ENCRYPTION_LEVEL.FormattingEnabled = true; + this.ENCRYPTION_LEVEL.Name = "ENCRYPTION_LEVEL"; + this.toolTip1.SetToolTip(this.ENCRYPTION_LEVEL, resources.GetString("ENCRYPTION_LEVEL.ToolTip")); + this.ENCRYPTION_LEVEL.SelectedValueChanged += new System.EventHandler(this.ENCRYPTION_LEVEL_CheckedChanged); + // + // RENCRYPTION_LEVEL + // + this.RENCRYPTION_LEVEL.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.RENCRYPTION_LEVEL, "RENCRYPTION_LEVEL"); + this.RENCRYPTION_LEVEL.FormattingEnabled = true; + this.RENCRYPTION_LEVEL.Name = "RENCRYPTION_LEVEL"; + this.toolTip1.SetToolTip(this.RENCRYPTION_LEVEL, resources.GetString("RENCRYPTION_LEVEL.ToolTip")); + this.RENCRYPTION_LEVEL.SelectedValueChanged += new System.EventHandler(this.RENCRYPTION_LEVEL_CheckedChanged); + // + // FSFRAMELOSS + // + this.FSFRAMELOSS.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.FSFRAMELOSS, "FSFRAMELOSS"); + this.FSFRAMELOSS.FormattingEnabled = true; + this.FSFRAMELOSS.Name = "FSFRAMELOSS"; + this.toolTip1.SetToolTip(this.FSFRAMELOSS, resources.GetString("FSFRAMELOSS.ToolTip")); + // + // RFSFRAMELOSS + // + this.RFSFRAMELOSS.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.RFSFRAMELOSS, "RFSFRAMELOSS"); + this.RFSFRAMELOSS.FormattingEnabled = true; + this.RFSFRAMELOSS.Name = "RFSFRAMELOSS"; + this.toolTip1.SetToolTip(this.RFSFRAMELOSS, resources.GetString("RFSFRAMELOSS.ToolTip")); + // + // GPO1_3SBUSIN + // + resources.ApplyResources(this.GPO1_3SBUSIN, "GPO1_3SBUSIN"); + this.GPO1_3SBUSIN.Name = "GPO1_3SBUSIN"; + // + // RGPO1_3SBUSIN + // + resources.ApplyResources(this.RGPO1_3SBUSIN, "RGPO1_3SBUSIN"); + this.RGPO1_3SBUSIN.Name = "RGPO1_3SBUSIN"; + // + // GPO1_3STATLED + // + resources.ApplyResources(this.GPO1_3STATLED, "GPO1_3STATLED"); + this.GPO1_3STATLED.Name = "GPO1_3STATLED"; + // + // GPO1_0TXEN485 + // + resources.ApplyResources(this.GPO1_0TXEN485, "GPO1_0TXEN485"); + this.GPO1_0TXEN485.Name = "GPO1_0TXEN485"; + // + // RGPO1_0TXEN485 + // + resources.ApplyResources(this.RGPO1_0TXEN485, "RGPO1_0TXEN485"); + this.RGPO1_0TXEN485.Name = "RGPO1_0TXEN485"; + // + // RGPO1_3STATLED + // + resources.ApplyResources(this.RGPO1_3STATLED, "RGPO1_3STATLED"); + this.RGPO1_3STATLED.Name = "RGPO1_3STATLED"; + // // RTI // resources.ApplyResources(this.RTI, "RTI"); @@ -766,8 +874,10 @@ private void InitializeComponent() // // lbl_status // + this.lbl_status.BackColor = System.Drawing.Color.Transparent; resources.ApplyResources(this.lbl_status, "lbl_status"); this.lbl_status.Name = "lbl_status"; + this.lbl_status.UseMnemonic = false; // // ATI3 // @@ -777,6 +887,30 @@ private void InitializeComponent() // // groupBoxLocal // + this.groupBoxLocal.Controls.Add(this.btnLoadFromFile); + this.groupBoxLocal.Controls.Add(this.btnSaveToFile); + this.groupBoxLocal.Controls.Add(this.label54); + this.groupBoxLocal.Controls.Add(this.FSFRAMELOSS); + this.groupBoxLocal.Controls.Add(this.GPO1_3AUXOUT); + this.groupBoxLocal.Controls.Add(this.lblGPO1_3AUXOUT); + this.groupBoxLocal.Controls.Add(this.GPI1_2AUXIN); + this.groupBoxLocal.Controls.Add(this.lblGPI1_2AUXIN); + this.groupBoxLocal.Controls.Add(this.lblGPIO1_1FUNC); + this.groupBoxLocal.Controls.Add(this.GPIO1_1FUNC); + this.groupBoxLocal.Controls.Add(this.ENCRYPTION_LEVEL); + this.groupBoxLocal.Controls.Add(this.GPO1_0TXEN485); + this.groupBoxLocal.Controls.Add(this.lblGPO1_0TXEN485); + this.groupBoxLocal.Controls.Add(this.GPO1_3STATLED); + this.groupBoxLocal.Controls.Add(this.lblGPO1_3STATLED); + this.groupBoxLocal.Controls.Add(this.GPO1_3SBUSOUT); + this.groupBoxLocal.Controls.Add(this.label49); + this.groupBoxLocal.Controls.Add(this.BUT_SetPPMFailSafe); + this.groupBoxLocal.Controls.Add(this.txtCountry); + this.groupBoxLocal.Controls.Add(this.label45); + this.groupBoxLocal.Controls.Add(this.RATE_FREQBAND); + this.groupBoxLocal.Controls.Add(this.lblSBUSOUT); + this.groupBoxLocal.Controls.Add(this.lblSBUSIN); + this.groupBoxLocal.Controls.Add(this.GPO1_3SBUSIN); this.groupBoxLocal.Controls.Add(this.btnRandom); this.groupBoxLocal.Controls.Add(this.lblRX_ENCAP_METHOD); this.groupBoxLocal.Controls.Add(this.RX_ENCAP_METHOD); @@ -786,9 +920,9 @@ private void InitializeComponent() this.groupBoxLocal.Controls.Add(this.lblNODEID); this.groupBoxLocal.Controls.Add(this.DESTID); this.groupBoxLocal.Controls.Add(this.NODEID); - this.groupBoxLocal.Controls.Add(this.label40); + this.groupBoxLocal.Controls.Add(this.lblGPO1_1R_COUT); this.groupBoxLocal.Controls.Add(this.GPO1_1R_COUT); - this.groupBoxLocal.Controls.Add(this.label39); + this.groupBoxLocal.Controls.Add(this.lblGPI1_1R_CIN); this.groupBoxLocal.Controls.Add(this.GPI1_1R_CIN); this.groupBoxLocal.Controls.Add(this.MAVLINK); this.groupBoxLocal.Controls.Add(this.label2); @@ -798,14 +932,14 @@ private void InitializeComponent() this.groupBoxLocal.Controls.Add(this.AIR_SPEED); this.groupBoxLocal.Controls.Add(this.label3); this.groupBoxLocal.Controls.Add(this.NETID); - this.groupBoxLocal.Controls.Add(this.label4); + this.groupBoxLocal.Controls.Add(this.lblNETID); this.groupBoxLocal.Controls.Add(this.TXPOWER); - this.groupBoxLocal.Controls.Add(this.label5); + this.groupBoxLocal.Controls.Add(this.lblTXPOWER); this.groupBoxLocal.Controls.Add(this.ECC); - this.groupBoxLocal.Controls.Add(this.label6); - this.groupBoxLocal.Controls.Add(this.label8); + this.groupBoxLocal.Controls.Add(this.lblECC); + this.groupBoxLocal.Controls.Add(this.lblOPPRESEND); this.groupBoxLocal.Controls.Add(this.OPPRESEND); - this.groupBoxLocal.Controls.Add(this.label7); + this.groupBoxLocal.Controls.Add(this.lblMAVLINK); this.groupBoxLocal.Controls.Add(this.lblANT_MODE); this.groupBoxLocal.Controls.Add(this.ANT_MODE); this.groupBoxLocal.Controls.Add(this.lblSER_BRK_DETMS); @@ -816,25 +950,24 @@ private void InitializeComponent() this.groupBoxLocal.Controls.Add(this.MAX_RETRIES); this.groupBoxLocal.Controls.Add(this.MAX_DATA); this.groupBoxLocal.Controls.Add(this.lblMAX_DATA); - this.groupBoxLocal.Controls.Add(this.ENCRYPTION_LEVEL); - this.groupBoxLocal.Controls.Add(this.label36); + this.groupBoxLocal.Controls.Add(this.lblENCRYPTION_LEVEL); this.groupBoxLocal.Controls.Add(this.label35); - this.groupBoxLocal.Controls.Add(this.txt_aeskey); + this.groupBoxLocal.Controls.Add(this.AESKEY); this.groupBoxLocal.Controls.Add(this.RTSCTS); - this.groupBoxLocal.Controls.Add(this.label19); + this.groupBoxLocal.Controls.Add(this.lblRTSCTS); this.groupBoxLocal.Controls.Add(this.linkLabel_mavlink); this.groupBoxLocal.Controls.Add(this.linkLabel_lowlatency); - this.groupBoxLocal.Controls.Add(this.label18); + this.groupBoxLocal.Controls.Add(this.lblMAX_WINDOW); this.groupBoxLocal.Controls.Add(this.MAX_WINDOW); - this.groupBoxLocal.Controls.Add(this.label13); + this.groupBoxLocal.Controls.Add(this.lblMIN_FREQ); this.groupBoxLocal.Controls.Add(this.MAX_FREQ); this.groupBoxLocal.Controls.Add(this.NUM_CHANNELS); - this.groupBoxLocal.Controls.Add(this.label17); + this.groupBoxLocal.Controls.Add(this.lblLBT_RSSI); this.groupBoxLocal.Controls.Add(this.LBT_RSSI); - this.groupBoxLocal.Controls.Add(this.label16); + this.groupBoxLocal.Controls.Add(this.lblDUTY_CYCLE); this.groupBoxLocal.Controls.Add(this.MIN_FREQ); - this.groupBoxLocal.Controls.Add(this.label15); - this.groupBoxLocal.Controls.Add(this.label14); + this.groupBoxLocal.Controls.Add(this.lblNUM_CHANNELS); + this.groupBoxLocal.Controls.Add(this.lblMAX_FREQ); this.groupBoxLocal.Controls.Add(this.DUTY_CYCLE); this.groupBoxLocal.Controls.Add(this.ATI2); this.groupBoxLocal.Controls.Add(this.ATI3); @@ -846,6 +979,93 @@ private void InitializeComponent() this.groupBoxLocal.Name = "groupBoxLocal"; this.groupBoxLocal.TabStop = false; // + // label54 + // + resources.ApplyResources(this.label54, "label54"); + this.label54.Name = "label54"; + // + // GPO1_3AUXOUT + // + resources.ApplyResources(this.GPO1_3AUXOUT, "GPO1_3AUXOUT"); + this.GPO1_3AUXOUT.Name = "GPO1_3AUXOUT"; + // + // lblGPO1_3AUXOUT + // + resources.ApplyResources(this.lblGPO1_3AUXOUT, "lblGPO1_3AUXOUT"); + this.lblGPO1_3AUXOUT.Name = "lblGPO1_3AUXOUT"; + // + // GPI1_2AUXIN + // + resources.ApplyResources(this.GPI1_2AUXIN, "GPI1_2AUXIN"); + this.GPI1_2AUXIN.Name = "GPI1_2AUXIN"; + // + // lblGPI1_2AUXIN + // + resources.ApplyResources(this.lblGPI1_2AUXIN, "lblGPI1_2AUXIN"); + this.lblGPI1_2AUXIN.Name = "lblGPI1_2AUXIN"; + // + // lblGPIO1_1FUNC + // + resources.ApplyResources(this.lblGPIO1_1FUNC, "lblGPIO1_1FUNC"); + this.lblGPIO1_1FUNC.Name = "lblGPIO1_1FUNC"; + // + // GPIO1_1FUNC + // + this.GPIO1_1FUNC.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.GPIO1_1FUNC, "GPIO1_1FUNC"); + this.GPIO1_1FUNC.FormattingEnabled = true; + this.GPIO1_1FUNC.Name = "GPIO1_1FUNC"; + // + // lblGPO1_0TXEN485 + // + resources.ApplyResources(this.lblGPO1_0TXEN485, "lblGPO1_0TXEN485"); + this.lblGPO1_0TXEN485.Name = "lblGPO1_0TXEN485"; + // + // lblGPO1_3STATLED + // + resources.ApplyResources(this.lblGPO1_3STATLED, "lblGPO1_3STATLED"); + this.lblGPO1_3STATLED.Name = "lblGPO1_3STATLED"; + // + // GPO1_3SBUSOUT + // + this.GPO1_3SBUSOUT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.GPO1_3SBUSOUT, "GPO1_3SBUSOUT"); + this.GPO1_3SBUSOUT.FormattingEnabled = true; + this.GPO1_3SBUSOUT.Name = "GPO1_3SBUSOUT"; + // + // label49 + // + resources.ApplyResources(this.label49, "label49"); + this.label49.Name = "label49"; + // + // txtCountry + // + resources.ApplyResources(this.txtCountry, "txtCountry"); + this.txtCountry.Name = "txtCountry"; + this.txtCountry.ReadOnly = true; + // + // label45 + // + resources.ApplyResources(this.label45, "label45"); + this.label45.Name = "label45"; + // + // RATE_FREQBAND + // + this.RATE_FREQBAND.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.RATE_FREQBAND, "RATE_FREQBAND"); + this.RATE_FREQBAND.FormattingEnabled = true; + this.RATE_FREQBAND.Name = "RATE_FREQBAND"; + // + // lblSBUSOUT + // + resources.ApplyResources(this.lblSBUSOUT, "lblSBUSOUT"); + this.lblSBUSOUT.Name = "lblSBUSOUT"; + // + // lblSBUSIN + // + resources.ApplyResources(this.lblSBUSIN, "lblSBUSIN"); + this.lblSBUSIN.Name = "lblSBUSIN"; + // // btnRandom // resources.ApplyResources(this.btnRandom, "btnRandom"); @@ -901,15 +1121,15 @@ private void InitializeComponent() this.NODEID.FormattingEnabled = true; this.NODEID.Name = "NODEID"; // - // label40 + // lblGPO1_1R_COUT // - resources.ApplyResources(this.label40, "label40"); - this.label40.Name = "label40"; + resources.ApplyResources(this.lblGPO1_1R_COUT, "lblGPO1_1R_COUT"); + this.lblGPO1_1R_COUT.Name = "lblGPO1_1R_COUT"; // - // label39 + // lblGPI1_1R_CIN // - resources.ApplyResources(this.label39, "label39"); - this.label39.Name = "label39"; + resources.ApplyResources(this.lblGPI1_1R_CIN, "lblGPI1_1R_CIN"); + this.lblGPI1_1R_CIN.Name = "lblGPI1_1R_CIN"; // // label2 // @@ -932,30 +1152,30 @@ private void InitializeComponent() resources.ApplyResources(this.label3, "label3"); this.label3.Name = "label3"; // - // label4 + // lblNETID // - resources.ApplyResources(this.label4, "label4"); - this.label4.Name = "label4"; + resources.ApplyResources(this.lblNETID, "lblNETID"); + this.lblNETID.Name = "lblNETID"; // - // label5 + // lblTXPOWER // - resources.ApplyResources(this.label5, "label5"); - this.label5.Name = "label5"; + resources.ApplyResources(this.lblTXPOWER, "lblTXPOWER"); + this.lblTXPOWER.Name = "lblTXPOWER"; // - // label6 + // lblECC // - resources.ApplyResources(this.label6, "label6"); - this.label6.Name = "label6"; + resources.ApplyResources(this.lblECC, "lblECC"); + this.lblECC.Name = "lblECC"; // - // label8 + // lblOPPRESEND // - resources.ApplyResources(this.label8, "label8"); - this.label8.Name = "label8"; + resources.ApplyResources(this.lblOPPRESEND, "lblOPPRESEND"); + this.lblOPPRESEND.Name = "lblOPPRESEND"; // - // label7 + // lblMAVLINK // - resources.ApplyResources(this.label7, "label7"); - this.label7.Name = "label7"; + resources.ApplyResources(this.lblMAVLINK, "lblMAVLINK"); + this.lblMAVLINK.Name = "lblMAVLINK"; // // lblANT_MODE // @@ -1017,75 +1237,67 @@ private void InitializeComponent() resources.ApplyResources(this.lblMAX_DATA, "lblMAX_DATA"); this.lblMAX_DATA.Name = "lblMAX_DATA"; // - // ENCRYPTION_LEVEL - // - resources.ApplyResources(this.ENCRYPTION_LEVEL, "ENCRYPTION_LEVEL"); - this.ENCRYPTION_LEVEL.Name = "ENCRYPTION_LEVEL"; - this.ENCRYPTION_LEVEL.CheckedChanged += new System.EventHandler(this.ENCRYPTION_LEVEL_CheckedChanged); + // lblENCRYPTION_LEVEL // - // label36 - // - resources.ApplyResources(this.label36, "label36"); - this.label36.Name = "label36"; + resources.ApplyResources(this.lblENCRYPTION_LEVEL, "lblENCRYPTION_LEVEL"); + this.lblENCRYPTION_LEVEL.Name = "lblENCRYPTION_LEVEL"; // // label35 // resources.ApplyResources(this.label35, "label35"); this.label35.Name = "label35"; // - // txt_aeskey + // txt_aeskeyraeskey // - resources.ApplyResources(this.txt_aeskey, "txt_aeskey"); - this.txt_aeskey.Name = "txt_aeskey"; + resources.ApplyResources(this.AESKEY, "txt_aeskey"); + this.AESKEY.Name = "AESKEY"; // - // label19 + // lblRTSCTS // - resources.ApplyResources(this.label19, "label19"); - this.label19.Name = "label19"; + resources.ApplyResources(this.lblRTSCTS, "lblRTSCTS"); + this.lblRTSCTS.Name = "lblRTSCTS"; // // linkLabel_mavlink // resources.ApplyResources(this.linkLabel_mavlink, "linkLabel_mavlink"); this.linkLabel_mavlink.Name = "linkLabel_mavlink"; this.linkLabel_mavlink.TabStop = true; - this.linkLabel_mavlink.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel_mavlink_LinkClicked); // // linkLabel_lowlatency // resources.ApplyResources(this.linkLabel_lowlatency, "linkLabel_lowlatency"); this.linkLabel_lowlatency.Name = "linkLabel_lowlatency"; this.linkLabel_lowlatency.TabStop = true; - this.linkLabel_lowlatency.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel_lowlatency_LinkClicked); // - // label18 + // lblMAX_WINDOW // - resources.ApplyResources(this.label18, "label18"); - this.label18.Name = "label18"; + resources.ApplyResources(this.lblMAX_WINDOW, "lblMAX_WINDOW"); + this.lblMAX_WINDOW.Name = "lblMAX_WINDOW"; // - // label13 + // lblMIN_FREQ // - resources.ApplyResources(this.label13, "label13"); - this.label13.Name = "label13"; + resources.ApplyResources(this.lblMIN_FREQ, "lblMIN_FREQ"); + this.lblMIN_FREQ.Name = "lblMIN_FREQ"; // - // label17 + // lblLBT_RSSI // - resources.ApplyResources(this.label17, "label17"); - this.label17.Name = "label17"; + resources.ApplyResources(this.lblLBT_RSSI, "lblLBT_RSSI"); + this.lblLBT_RSSI.Name = "lblLBT_RSSI"; // - // label16 + // lblDUTY_CYCLE // - resources.ApplyResources(this.label16, "label16"); - this.label16.Name = "label16"; + resources.ApplyResources(this.lblDUTY_CYCLE, "lblDUTY_CYCLE"); + this.lblDUTY_CYCLE.Name = "lblDUTY_CYCLE"; // - // label15 + // lblNUM_CHANNELS // - resources.ApplyResources(this.label15, "label15"); - this.label15.Name = "label15"; + resources.ApplyResources(this.lblNUM_CHANNELS, "lblNUM_CHANNELS"); + this.lblNUM_CHANNELS.Name = "lblNUM_CHANNELS"; // - // label14 + // lblMAX_FREQ // - resources.ApplyResources(this.label14, "label14"); - this.label14.Name = "label14"; + resources.ApplyResources(this.lblMAX_FREQ, "lblMAX_FREQ"); + this.lblMAX_FREQ.Name = "lblMAX_FREQ"; // // ATI2 // @@ -1095,6 +1307,30 @@ private void InitializeComponent() // // groupBoxRemote // + this.groupBoxRemote.Controls.Add(this.btnRemoteLoadFromFile); + this.groupBoxRemote.Controls.Add(this.btnRemoteSaveToFile); + this.groupBoxRemote.Controls.Add(this.lblRFSFRAMELOSS); + this.groupBoxRemote.Controls.Add(this.RFSFRAMELOSS); + this.groupBoxRemote.Controls.Add(this.RGPO1_3AUXOUT); + this.groupBoxRemote.Controls.Add(this.lblRGPO1_3AUXOUT); + this.groupBoxRemote.Controls.Add(this.RGPI1_2AUXIN); + this.groupBoxRemote.Controls.Add(this.lblRGPI1_2AUXIN); + this.groupBoxRemote.Controls.Add(this.lblRGPIO1_1FUNC); + this.groupBoxRemote.Controls.Add(this.RGPIO1_1FUNC); + this.groupBoxRemote.Controls.Add(this.RENCRYPTION_LEVEL); + this.groupBoxRemote.Controls.Add(this.RGPO1_0TXEN485); + this.groupBoxRemote.Controls.Add(this.lblRGPO1_0TXEN485); + this.groupBoxRemote.Controls.Add(this.RGPO1_3STATLED); + this.groupBoxRemote.Controls.Add(this.lblRGPO1_3STATLED); + this.groupBoxRemote.Controls.Add(this.RGPO1_3SBUSOUT); + this.groupBoxRemote.Controls.Add(this.BUT_SetPPMFailSafeRemote); + this.groupBoxRemote.Controls.Add(this.label50); + this.groupBoxRemote.Controls.Add(this.txtRCountry); + this.groupBoxRemote.Controls.Add(this.lblRSBUSOUT); + this.groupBoxRemote.Controls.Add(this.lblRSBUSIN); + this.groupBoxRemote.Controls.Add(this.RGPO1_3SBUSIN); + this.groupBoxRemote.Controls.Add(this.label46); + this.groupBoxRemote.Controls.Add(this.RRATE_FREQBAND); this.groupBoxRemote.Controls.Add(this.lblRRX_ENCAP_METHOD); this.groupBoxRemote.Controls.Add(this.RRX_ENCAP_METHOD); this.groupBoxRemote.Controls.Add(this.lblRTX_ENCAP_METHOD); @@ -1103,23 +1339,23 @@ private void InitializeComponent() this.groupBoxRemote.Controls.Add(this.lblRNODEID); this.groupBoxRemote.Controls.Add(this.RDESTID); this.groupBoxRemote.Controls.Add(this.RNODEID); - this.groupBoxRemote.Controls.Add(this.label41); + this.groupBoxRemote.Controls.Add(this.lblRGPO1_1R_COUT); this.groupBoxRemote.Controls.Add(this.RMAVLINK); this.groupBoxRemote.Controls.Add(this.RGPO1_1R_COUT); this.groupBoxRemote.Controls.Add(this.RFORMAT); - this.groupBoxRemote.Controls.Add(this.label42); + this.groupBoxRemote.Controls.Add(this.lblRGPI1_1R_CIN); this.groupBoxRemote.Controls.Add(this.RGPI1_1R_CIN); this.groupBoxRemote.Controls.Add(this.RSERIAL_SPEED); this.groupBoxRemote.Controls.Add(this.RAIR_SPEED); this.groupBoxRemote.Controls.Add(this.RNETID); - this.groupBoxRemote.Controls.Add(this.label25); + this.groupBoxRemote.Controls.Add(this.lblROPPRESEND); this.groupBoxRemote.Controls.Add(this.RTXPOWER); - this.groupBoxRemote.Controls.Add(this.label26); + this.groupBoxRemote.Controls.Add(this.lblRMAVLINK); this.groupBoxRemote.Controls.Add(this.RECC); - this.groupBoxRemote.Controls.Add(this.label27); - this.groupBoxRemote.Controls.Add(this.label28); + this.groupBoxRemote.Controls.Add(this.lblRECC); + this.groupBoxRemote.Controls.Add(this.lblRTXPOWER); this.groupBoxRemote.Controls.Add(this.ROPPRESEND); - this.groupBoxRemote.Controls.Add(this.label29); + this.groupBoxRemote.Controls.Add(this.lblRNETID); this.groupBoxRemote.Controls.Add(this.label32); this.groupBoxRemote.Controls.Add(this.label30); this.groupBoxRemote.Controls.Add(this.label31); @@ -1134,23 +1370,22 @@ private void InitializeComponent() this.groupBoxRemote.Controls.Add(this.RMAX_DATA); this.groupBoxRemote.Controls.Add(this.lblRMAX_DATA); this.groupBoxRemote.Controls.Add(this.label38); - this.groupBoxRemote.Controls.Add(this.RENCRYPTION_LEVEL); - this.groupBoxRemote.Controls.Add(this.txt_Raeskey); - this.groupBoxRemote.Controls.Add(this.label37); + this.groupBoxRemote.Controls.Add(this.RAESKEY); + this.groupBoxRemote.Controls.Add(this.lblRENCRYPTION_LEVEL); this.groupBoxRemote.Controls.Add(this.RRTSCTS); - this.groupBoxRemote.Controls.Add(this.label33); - this.groupBoxRemote.Controls.Add(this.label34); + this.groupBoxRemote.Controls.Add(this.lblRRTSCTS); + this.groupBoxRemote.Controls.Add(this.lblRMAX_WINDOW); this.groupBoxRemote.Controls.Add(this.RMAX_WINDOW); - this.groupBoxRemote.Controls.Add(this.label24); + this.groupBoxRemote.Controls.Add(this.lblRMIN_FREQ); this.groupBoxRemote.Controls.Add(this.RMAX_FREQ); this.groupBoxRemote.Controls.Add(this.RNUM_CHANNELS); this.groupBoxRemote.Controls.Add(this.RDUTY_CYCLE); this.groupBoxRemote.Controls.Add(this.RLBT_RSSI); this.groupBoxRemote.Controls.Add(this.RMIN_FREQ); - this.groupBoxRemote.Controls.Add(this.label23); - this.groupBoxRemote.Controls.Add(this.label22); - this.groupBoxRemote.Controls.Add(this.label21); - this.groupBoxRemote.Controls.Add(this.label20); + this.groupBoxRemote.Controls.Add(this.lblRMAX_FREQ); + this.groupBoxRemote.Controls.Add(this.lblRNUM_CHANNELS); + this.groupBoxRemote.Controls.Add(this.lblRDUTY_CYCLE); + this.groupBoxRemote.Controls.Add(this.lblRLBT_RSSI); this.groupBoxRemote.Controls.Add(this.RTI2); this.groupBoxRemote.Controls.Add(this.label9); this.groupBoxRemote.Controls.Add(this.RTI); @@ -1158,6 +1393,93 @@ private void InitializeComponent() this.groupBoxRemote.Name = "groupBoxRemote"; this.groupBoxRemote.TabStop = false; // + // lblRFSFRAMELOSS + // + resources.ApplyResources(this.lblRFSFRAMELOSS, "lblRFSFRAMELOSS"); + this.lblRFSFRAMELOSS.Name = "lblRFSFRAMELOSS"; + // + // RGPO1_3AUXOUT + // + resources.ApplyResources(this.RGPO1_3AUXOUT, "RGPO1_3AUXOUT"); + this.RGPO1_3AUXOUT.Name = "RGPO1_3AUXOUT"; + // + // lblRGPO1_3AUXOUT + // + resources.ApplyResources(this.lblRGPO1_3AUXOUT, "lblRGPO1_3AUXOUT"); + this.lblRGPO1_3AUXOUT.Name = "lblRGPO1_3AUXOUT"; + // + // RGPI1_2AUXIN + // + resources.ApplyResources(this.RGPI1_2AUXIN, "RGPI1_2AUXIN"); + this.RGPI1_2AUXIN.Name = "RGPI1_2AUXIN"; + // + // lblRGPI1_2AUXIN + // + resources.ApplyResources(this.lblRGPI1_2AUXIN, "lblRGPI1_2AUXIN"); + this.lblRGPI1_2AUXIN.Name = "lblRGPI1_2AUXIN"; + // + // lblRGPIO1_1FUNC + // + resources.ApplyResources(this.lblRGPIO1_1FUNC, "lblRGPIO1_1FUNC"); + this.lblRGPIO1_1FUNC.Name = "lblRGPIO1_1FUNC"; + // + // RGPIO1_1FUNC + // + this.RGPIO1_1FUNC.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.RGPIO1_1FUNC, "RGPIO1_1FUNC"); + this.RGPIO1_1FUNC.FormattingEnabled = true; + this.RGPIO1_1FUNC.Name = "RGPIO1_1FUNC"; + // + // lblRGPO1_0TXEN485 + // + resources.ApplyResources(this.lblRGPO1_0TXEN485, "lblRGPO1_0TXEN485"); + this.lblRGPO1_0TXEN485.Name = "lblRGPO1_0TXEN485"; + // + // lblRGPO1_3STATLED + // + resources.ApplyResources(this.lblRGPO1_3STATLED, "lblRGPO1_3STATLED"); + this.lblRGPO1_3STATLED.Name = "lblRGPO1_3STATLED"; + // + // RGPO1_3SBUSOUT + // + this.RGPO1_3SBUSOUT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.RGPO1_3SBUSOUT, "RGPO1_3SBUSOUT"); + this.RGPO1_3SBUSOUT.FormattingEnabled = true; + this.RGPO1_3SBUSOUT.Name = "RGPO1_3SBUSOUT"; + // + // label50 + // + resources.ApplyResources(this.label50, "label50"); + this.label50.Name = "label50"; + // + // txtRCountry + // + resources.ApplyResources(this.txtRCountry, "txtRCountry"); + this.txtRCountry.Name = "txtRCountry"; + this.txtRCountry.ReadOnly = true; + // + // lblRSBUSOUT + // + resources.ApplyResources(this.lblRSBUSOUT, "lblRSBUSOUT"); + this.lblRSBUSOUT.Name = "lblRSBUSOUT"; + // + // lblRSBUSIN + // + resources.ApplyResources(this.lblRSBUSIN, "lblRSBUSIN"); + this.lblRSBUSIN.Name = "lblRSBUSIN"; + // + // label46 + // + resources.ApplyResources(this.label46, "label46"); + this.label46.Name = "label46"; + // + // RRATE_FREQBAND + // + this.RRATE_FREQBAND.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; + resources.ApplyResources(this.RRATE_FREQBAND, "RRATE_FREQBAND"); + this.RRATE_FREQBAND.FormattingEnabled = true; + this.RRATE_FREQBAND.Name = "RRATE_FREQBAND"; + // // lblRRX_ENCAP_METHOD // resources.ApplyResources(this.lblRRX_ENCAP_METHOD, "lblRRX_ENCAP_METHOD"); @@ -1206,10 +1528,10 @@ private void InitializeComponent() resources.ApplyResources(this.RNODEID, "RNODEID"); this.RNODEID.Name = "RNODEID"; // - // label41 + // lblRGPO1_1R_COUT // - resources.ApplyResources(this.label41, "label41"); - this.label41.Name = "label41"; + resources.ApplyResources(this.lblRGPO1_1R_COUT, "lblRGPO1_1R_COUT"); + this.lblRGPO1_1R_COUT.Name = "lblRGPO1_1R_COUT"; // // RFORMAT // @@ -1217,35 +1539,35 @@ private void InitializeComponent() this.RFORMAT.Name = "RFORMAT"; this.RFORMAT.ReadOnly = true; // - // label42 + // lblRGPI1_1R_CIN // - resources.ApplyResources(this.label42, "label42"); - this.label42.Name = "label42"; + resources.ApplyResources(this.lblRGPI1_1R_CIN, "lblRGPI1_1R_CIN"); + this.lblRGPI1_1R_CIN.Name = "lblRGPI1_1R_CIN"; // - // label25 + // lblROPPRESEND // - resources.ApplyResources(this.label25, "label25"); - this.label25.Name = "label25"; + resources.ApplyResources(this.lblROPPRESEND, "lblROPPRESEND"); + this.lblROPPRESEND.Name = "lblROPPRESEND"; // - // label26 + // lblRMAVLINK // - resources.ApplyResources(this.label26, "label26"); - this.label26.Name = "label26"; + resources.ApplyResources(this.lblRMAVLINK, "lblRMAVLINK"); + this.lblRMAVLINK.Name = "lblRMAVLINK"; // - // label27 + // lblRECC // - resources.ApplyResources(this.label27, "label27"); - this.label27.Name = "label27"; + resources.ApplyResources(this.lblRECC, "lblRECC"); + this.lblRECC.Name = "lblRECC"; // - // label28 + // lblRTXPOWER // - resources.ApplyResources(this.label28, "label28"); - this.label28.Name = "label28"; + resources.ApplyResources(this.lblRTXPOWER, "lblRTXPOWER"); + this.lblRTXPOWER.Name = "lblRTXPOWER"; // - // label29 + // lblRNETID // - resources.ApplyResources(this.label29, "label29"); - this.label29.Name = "label29"; + resources.ApplyResources(this.lblRNETID, "lblRNETID"); + this.lblRNETID.Name = "lblRNETID"; // // label32 // @@ -1270,8 +1592,8 @@ private void InitializeComponent() // RANT_MODE // this.RANT_MODE.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; - this.RANT_MODE.FormattingEnabled = true; resources.ApplyResources(this.RANT_MODE, "RANT_MODE"); + this.RANT_MODE.FormattingEnabled = true; this.RANT_MODE.Name = "RANT_MODE"; // // lblRSER_BRK_DETMS @@ -1327,56 +1649,50 @@ private void InitializeComponent() resources.ApplyResources(this.label38, "label38"); this.label38.Name = "label38"; // - // RENCRYPTION_LEVEL - // - resources.ApplyResources(this.RENCRYPTION_LEVEL, "RENCRYPTION_LEVEL"); - this.RENCRYPTION_LEVEL.Name = "RENCRYPTION_LEVEL"; - this.RENCRYPTION_LEVEL.CheckedChanged += new System.EventHandler(this.RENCRYPTION_LEVEL_CheckedChanged); - // // txt_Raeskey // - resources.ApplyResources(this.txt_Raeskey, "txt_Raeskey"); - this.txt_Raeskey.Name = "txt_Raeskey"; + resources.ApplyResources(this.RAESKEY, "txt_Raeskey"); + this.RAESKEY.Name = "RAESKEY"; // - // label37 + // lblRENCRYPTION_LEVEL // - resources.ApplyResources(this.label37, "label37"); - this.label37.Name = "label37"; + resources.ApplyResources(this.lblRENCRYPTION_LEVEL, "lblRENCRYPTION_LEVEL"); + this.lblRENCRYPTION_LEVEL.Name = "lblRENCRYPTION_LEVEL"; // - // label33 + // lblRRTSCTS // - resources.ApplyResources(this.label33, "label33"); - this.label33.Name = "label33"; + resources.ApplyResources(this.lblRRTSCTS, "lblRRTSCTS"); + this.lblRRTSCTS.Name = "lblRRTSCTS"; // - // label34 + // lblRMAX_WINDOW // - resources.ApplyResources(this.label34, "label34"); - this.label34.Name = "label34"; + resources.ApplyResources(this.lblRMAX_WINDOW, "lblRMAX_WINDOW"); + this.lblRMAX_WINDOW.Name = "lblRMAX_WINDOW"; // - // label24 + // lblRMIN_FREQ // - resources.ApplyResources(this.label24, "label24"); - this.label24.Name = "label24"; + resources.ApplyResources(this.lblRMIN_FREQ, "lblRMIN_FREQ"); + this.lblRMIN_FREQ.Name = "lblRMIN_FREQ"; // - // label23 + // lblRMAX_FREQ // - resources.ApplyResources(this.label23, "label23"); - this.label23.Name = "label23"; + resources.ApplyResources(this.lblRMAX_FREQ, "lblRMAX_FREQ"); + this.lblRMAX_FREQ.Name = "lblRMAX_FREQ"; // - // label22 + // lblRNUM_CHANNELS // - resources.ApplyResources(this.label22, "label22"); - this.label22.Name = "label22"; + resources.ApplyResources(this.lblRNUM_CHANNELS, "lblRNUM_CHANNELS"); + this.lblRNUM_CHANNELS.Name = "lblRNUM_CHANNELS"; // - // label21 + // lblRDUTY_CYCLE // - resources.ApplyResources(this.label21, "label21"); - this.label21.Name = "label21"; + resources.ApplyResources(this.lblRDUTY_CYCLE, "lblRDUTY_CYCLE"); + this.lblRDUTY_CYCLE.Name = "lblRDUTY_CYCLE"; // - // label20 + // lblRLBT_RSSI // - resources.ApplyResources(this.label20, "label20"); - this.label20.Name = "label20"; + resources.ApplyResources(this.lblRLBT_RSSI, "lblRLBT_RSSI"); + this.lblRLBT_RSSI.Name = "lblRLBT_RSSI"; // // RTI2 // @@ -1394,13 +1710,15 @@ private void InitializeComponent() resources.ApplyResources(this.label10, "label10"); this.label10.Name = "label10"; // - // BUT_SetPPMFailSafe + // dlgSave // - resources.ApplyResources(this.BUT_SetPPMFailSafe, "BUT_SetPPMFailSafe"); - this.BUT_SetPPMFailSafe.Name = "BUT_SetPPMFailSafe"; - this.toolTip1.SetToolTip(this.BUT_SetPPMFailSafe, resources.GetString("BUT_SetPPMFailSafe.ToolTip")); - this.BUT_SetPPMFailSafe.UseVisualStyleBackColor = true; - this.BUT_SetPPMFailSafe.Click += new System.EventHandler(this.BUT_SetPPMFailSafe_Click); + this.dlgSave.FileName = "*.ini"; + resources.ApplyResources(this.dlgSave, "dlgSave"); + // + // dlgOpen + // + this.dlgOpen.FileName = "*.ini"; + resources.ApplyResources(this.dlgOpen, "dlgOpen"); // // BUT_loadcustom // @@ -1416,6 +1734,36 @@ private void InitializeComponent() this.BUT_resettodefault.UseVisualStyleBackColor = true; this.BUT_resettodefault.Click += new System.EventHandler(this.BUT_resettodefault_Click); // + // btnRemoteLoadFromFile + // + resources.ApplyResources(this.btnRemoteLoadFromFile, "btnRemoteLoadFromFile"); + this.btnRemoteLoadFromFile.Name = "btnRemoteLoadFromFile"; + this.btnRemoteLoadFromFile.UseVisualStyleBackColor = true; + this.btnRemoteLoadFromFile.Click += new System.EventHandler(this.btnRemoteLoadFromFile_Click); + // + // btnRemoteSaveToFile + // + resources.ApplyResources(this.btnRemoteSaveToFile, "btnRemoteSaveToFile"); + this.btnRemoteSaveToFile.Name = "btnRemoteSaveToFile"; + this.btnRemoteSaveToFile.UseVisualStyleBackColor = true; + this.btnRemoteSaveToFile.Click += new System.EventHandler(this.btnRemoteSaveToFile_Click); + // + // BUT_SetPPMFailSafeRemote + // + resources.ApplyResources(this.BUT_SetPPMFailSafeRemote, "BUT_SetPPMFailSafeRemote"); + this.BUT_SetPPMFailSafeRemote.Name = "BUT_SetPPMFailSafeRemote"; + this.toolTip1.SetToolTip(this.BUT_SetPPMFailSafeRemote, resources.GetString("BUT_SetPPMFailSafeRemote.ToolTip")); + this.BUT_SetPPMFailSafeRemote.UseVisualStyleBackColor = true; + this.BUT_SetPPMFailSafeRemote.Click += new System.EventHandler(this.BUT_SetPPMFailSafeRemote_Click); + // + // BUT_SetPPMFailSafe + // + resources.ApplyResources(this.BUT_SetPPMFailSafe, "BUT_SetPPMFailSafe"); + this.BUT_SetPPMFailSafe.Name = "BUT_SetPPMFailSafe"; + this.toolTip1.SetToolTip(this.BUT_SetPPMFailSafe, resources.GetString("BUT_SetPPMFailSafe.ToolTip")); + this.BUT_SetPPMFailSafe.UseVisualStyleBackColor = true; + this.BUT_SetPPMFailSafe.Click += new System.EventHandler(this.BUT_SetPPMFailSafe_Click); + // // BUT_savesettings // resources.ApplyResources(this.BUT_savesettings, "BUT_savesettings"); @@ -1444,11 +1792,24 @@ private void InitializeComponent() this.BUT_Syncoptions.UseVisualStyleBackColor = true; this.BUT_Syncoptions.Click += new System.EventHandler(this.BUT_Syncoptions_Click); // + // btnSaveToFile + // + resources.ApplyResources(this.btnSaveToFile, "btnSaveToFile"); + this.btnSaveToFile.Name = "btnSaveToFile"; + this.btnSaveToFile.UseVisualStyleBackColor = true; + this.btnSaveToFile.Click += new System.EventHandler(this.btnSaveToFile_Click); + // + // btnLoadFromFile + // + resources.ApplyResources(this.btnLoadFromFile, "btnLoadFromFile"); + this.btnLoadFromFile.Name = "btnLoadFromFile"; + this.btnLoadFromFile.UseVisualStyleBackColor = true; + this.btnLoadFromFile.Click += new System.EventHandler(this.btnLoadFromFile_Click); + // // Sikradio // this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.None; this.Controls.Add(this.Progressbar); - this.Controls.Add(this.BUT_SetPPMFailSafe); this.Controls.Add(this.BUT_loadcustom); this.Controls.Add(this.BUT_resettodefault); this.Controls.Add(this.linkLabel1); @@ -1469,147 +1830,194 @@ private void InitializeComponent() this.ResumeLayout(false); this.PerformLayout(); - } - - #endregion - - private Controls.MyButton BUT_upload; - private System.Windows.Forms.ProgressBar Progressbar; - private System.Windows.Forms.Label lbl_status; - private Controls.MyButton BUT_getcurrent; - private Controls.MyButton BUT_savesettings; - private System.Windows.Forms.ToolTip toolTip1; - private System.Windows.Forms.TextBox RTI; - private System.Windows.Forms.TextBox ATI; - private System.Windows.Forms.TextBox RSSI; - private System.Windows.Forms.Label label11; - private System.Windows.Forms.Label label12; - private Controls.MyButton BUT_Syncoptions; - private System.Windows.Forms.TextBox ATI3; - private System.Windows.Forms.GroupBox groupBoxLocal; - private System.Windows.Forms.GroupBox groupBoxRemote; - private System.Windows.Forms.Label label9; - private System.Windows.Forms.Label label10; - private System.Windows.Forms.LinkLabel linkLabel1; - private Controls.MyButton BUT_resettodefault; - private System.Windows.Forms.TextBox ATI2; - private System.Windows.Forms.TextBox RTI2; - private Controls.MyButton BUT_loadcustom; - private Controls.MyButton BUT_SetPPMFailSafe; - private System.Windows.Forms.Label lblRX_ENCAP_METHOD; - private System.Windows.Forms.ComboBox RX_ENCAP_METHOD; - private System.Windows.Forms.Label lblTX_ENCAP_METHOD; - private System.Windows.Forms.ComboBox TX_ENCAP_METHOD; - private System.Windows.Forms.Label lblDESTID; - private System.Windows.Forms.Label lblNODEID; - private System.Windows.Forms.ComboBox DESTID; - private System.Windows.Forms.ComboBox NODEID; - private System.Windows.Forms.Label label40; - private System.Windows.Forms.CheckBox GPO1_1R_COUT; - private System.Windows.Forms.Label label39; - private System.Windows.Forms.CheckBox GPI1_1R_CIN; - private System.Windows.Forms.ComboBox MAVLINK; - private System.Windows.Forms.Label label2; - private System.Windows.Forms.ComboBox SERIAL_SPEED; - private System.Windows.Forms.Label label1; - private System.Windows.Forms.TextBox FORMAT; - private System.Windows.Forms.ComboBox AIR_SPEED; - private System.Windows.Forms.Label label3; - private System.Windows.Forms.ComboBox NETID; - private System.Windows.Forms.Label label4; - private System.Windows.Forms.ComboBox TXPOWER; - private System.Windows.Forms.Label label5; - private System.Windows.Forms.CheckBox ECC; - private System.Windows.Forms.Label label6; - private System.Windows.Forms.Label label8; - private System.Windows.Forms.CheckBox OPPRESEND; - private System.Windows.Forms.Label label7; - private System.Windows.Forms.Label lblANT_MODE; - private System.Windows.Forms.ComboBox ANT_MODE; - private System.Windows.Forms.Label lblSER_BRK_DETMS; - private System.Windows.Forms.Label lblGLOBAL_RETRIES; - private System.Windows.Forms.Label lblMAX_RETRIES; - private System.Windows.Forms.ComboBox SER_BRK_DETMS; - private System.Windows.Forms.ComboBox GLOBAL_RETRIES; - private System.Windows.Forms.ComboBox MAX_RETRIES; - private System.Windows.Forms.ComboBox MAX_DATA; - private System.Windows.Forms.Label lblMAX_DATA; - private System.Windows.Forms.CheckBox ENCRYPTION_LEVEL; - private System.Windows.Forms.Label label36; - private System.Windows.Forms.Label label35; - private System.Windows.Forms.TextBox txt_aeskey; - private System.Windows.Forms.CheckBox RTSCTS; - private System.Windows.Forms.Label label19; - private System.Windows.Forms.LinkLabel linkLabel_mavlink; - private System.Windows.Forms.LinkLabel linkLabel_lowlatency; - private System.Windows.Forms.Label label18; - private System.Windows.Forms.ComboBox MAX_WINDOW; - private System.Windows.Forms.Label label13; - private System.Windows.Forms.ComboBox MAX_FREQ; - private System.Windows.Forms.ComboBox NUM_CHANNELS; - private System.Windows.Forms.Label label17; - private System.Windows.Forms.ComboBox LBT_RSSI; - private System.Windows.Forms.Label label16; - private System.Windows.Forms.ComboBox MIN_FREQ; - private System.Windows.Forms.Label label15; - private System.Windows.Forms.Label label14; - private System.Windows.Forms.ComboBox DUTY_CYCLE; - private System.Windows.Forms.Label lblRRX_ENCAP_METHOD; - private System.Windows.Forms.ComboBox RRX_ENCAP_METHOD; - private System.Windows.Forms.Label lblRTX_ENCAP_METHOD; - private System.Windows.Forms.ComboBox RTX_ENCAP_METHOD; - private System.Windows.Forms.Label lblRDESTID; - private System.Windows.Forms.Label lblRNODEID; - private System.Windows.Forms.ComboBox RDESTID; - private System.Windows.Forms.ComboBox RNODEID; - private System.Windows.Forms.Label label41; - private System.Windows.Forms.ComboBox RMAVLINK; - private System.Windows.Forms.CheckBox RGPO1_1R_COUT; - private System.Windows.Forms.TextBox RFORMAT; - private System.Windows.Forms.Label label42; - private System.Windows.Forms.CheckBox RGPI1_1R_CIN; - private System.Windows.Forms.ComboBox RSERIAL_SPEED; - private System.Windows.Forms.ComboBox RAIR_SPEED; - private System.Windows.Forms.ComboBox RNETID; - private System.Windows.Forms.Label label25; - private System.Windows.Forms.ComboBox RTXPOWER; - private System.Windows.Forms.Label label26; - private System.Windows.Forms.CheckBox RECC; - private System.Windows.Forms.Label label27; - private System.Windows.Forms.Label label28; - private System.Windows.Forms.CheckBox ROPPRESEND; - private System.Windows.Forms.Label label29; - private System.Windows.Forms.Label label32; - private System.Windows.Forms.Label label30; - private System.Windows.Forms.Label label31; - private System.Windows.Forms.Label lblRANT_MODE; - private System.Windows.Forms.ComboBox RANT_MODE; - private System.Windows.Forms.Label lblRSER_BRK_DETMS; - private System.Windows.Forms.Label lblRGLOBAL_RETRIES; - private System.Windows.Forms.Label lblRMAX_RETRIES; - private System.Windows.Forms.ComboBox RSER_BRK_DETMS; - private System.Windows.Forms.ComboBox RGLOBAL_RETRIES; - private System.Windows.Forms.ComboBox RMAX_RETRIES; - private System.Windows.Forms.ComboBox RMAX_DATA; - private System.Windows.Forms.Label lblRMAX_DATA; - private System.Windows.Forms.Label label38; - private System.Windows.Forms.CheckBox RENCRYPTION_LEVEL; - private System.Windows.Forms.TextBox txt_Raeskey; - private System.Windows.Forms.Label label37; - private System.Windows.Forms.CheckBox RRTSCTS; - private System.Windows.Forms.Label label33; - private System.Windows.Forms.Label label34; - private System.Windows.Forms.ComboBox RMAX_WINDOW; - private System.Windows.Forms.Label label24; - private System.Windows.Forms.ComboBox RMAX_FREQ; - private System.Windows.Forms.ComboBox RNUM_CHANNELS; - private System.Windows.Forms.ComboBox RDUTY_CYCLE; - private System.Windows.Forms.ComboBox RLBT_RSSI; - private System.Windows.Forms.ComboBox RMIN_FREQ; - private System.Windows.Forms.Label label23; - private System.Windows.Forms.Label label22; - private System.Windows.Forms.Label label21; - private System.Windows.Forms.Label label20; - private System.Windows.Forms.Button btnRandom; - } + } + + #endregion + + private Controls.MyButton BUT_upload; + private System.Windows.Forms.ProgressBar Progressbar; + private System.Windows.Forms.Label lbl_status; + private Controls.MyButton BUT_getcurrent; + private Controls.MyButton BUT_savesettings; + private System.Windows.Forms.ToolTip toolTip1; + private System.Windows.Forms.TextBox RTI; + private System.Windows.Forms.TextBox ATI; + private System.Windows.Forms.TextBox RSSI; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label12; + private Controls.MyButton BUT_Syncoptions; + private System.Windows.Forms.TextBox ATI3; + private System.Windows.Forms.GroupBox groupBoxLocal; + private System.Windows.Forms.GroupBox groupBoxRemote; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.LinkLabel linkLabel1; + private Controls.MyButton BUT_resettodefault; + private System.Windows.Forms.TextBox ATI2; + private System.Windows.Forms.TextBox RTI2; + private Controls.MyButton BUT_loadcustom; + private Controls.MyButton BUT_SetPPMFailSafe; + private System.Windows.Forms.Label lblRX_ENCAP_METHOD; + private System.Windows.Forms.ComboBox RX_ENCAP_METHOD; + private System.Windows.Forms.Label lblTX_ENCAP_METHOD; + private System.Windows.Forms.ComboBox TX_ENCAP_METHOD; + private System.Windows.Forms.Label lblDESTID; + private System.Windows.Forms.Label lblNODEID; + private System.Windows.Forms.ComboBox DESTID; + private System.Windows.Forms.ComboBox NODEID; + private System.Windows.Forms.Label lblGPO1_1R_COUT; + private System.Windows.Forms.CheckBox GPO1_1R_COUT; + private System.Windows.Forms.Label lblGPI1_1R_CIN; + private System.Windows.Forms.CheckBox GPI1_1R_CIN; + private System.Windows.Forms.ComboBox MAVLINK; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.ComboBox SERIAL_SPEED; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.TextBox FORMAT; + private System.Windows.Forms.ComboBox AIR_SPEED; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.ComboBox NETID; + private System.Windows.Forms.Label lblNETID; + private System.Windows.Forms.ComboBox TXPOWER; + private System.Windows.Forms.Label lblTXPOWER; + private System.Windows.Forms.CheckBox ECC; + private System.Windows.Forms.Label lblECC; + private System.Windows.Forms.Label lblOPPRESEND; + private System.Windows.Forms.CheckBox OPPRESEND; + private System.Windows.Forms.Label lblMAVLINK; + private System.Windows.Forms.Label lblANT_MODE; + private System.Windows.Forms.ComboBox ANT_MODE; + private System.Windows.Forms.Label lblSER_BRK_DETMS; + private System.Windows.Forms.Label lblGLOBAL_RETRIES; + private System.Windows.Forms.Label lblMAX_RETRIES; + private System.Windows.Forms.ComboBox SER_BRK_DETMS; + private System.Windows.Forms.ComboBox GLOBAL_RETRIES; + private System.Windows.Forms.ComboBox MAX_RETRIES; + private System.Windows.Forms.ComboBox MAX_DATA; + private System.Windows.Forms.Label lblMAX_DATA; + private System.Windows.Forms.Label lblENCRYPTION_LEVEL; + private System.Windows.Forms.Label label35; + private System.Windows.Forms.TextBox AESKEY; + private System.Windows.Forms.CheckBox RTSCTS; + private System.Windows.Forms.Label lblRTSCTS; + private System.Windows.Forms.LinkLabel linkLabel_mavlink; + private System.Windows.Forms.LinkLabel linkLabel_lowlatency; + private System.Windows.Forms.Label lblMAX_WINDOW; + private System.Windows.Forms.ComboBox MAX_WINDOW; + private System.Windows.Forms.Label lblMIN_FREQ; + private System.Windows.Forms.ComboBox MAX_FREQ; + private System.Windows.Forms.ComboBox NUM_CHANNELS; + private System.Windows.Forms.Label lblLBT_RSSI; + private System.Windows.Forms.ComboBox LBT_RSSI; + private System.Windows.Forms.Label lblDUTY_CYCLE; + private System.Windows.Forms.ComboBox MIN_FREQ; + private System.Windows.Forms.Label lblNUM_CHANNELS; + private System.Windows.Forms.Label lblMAX_FREQ; + private System.Windows.Forms.ComboBox DUTY_CYCLE; + private System.Windows.Forms.Label lblRRX_ENCAP_METHOD; + private System.Windows.Forms.ComboBox RRX_ENCAP_METHOD; + private System.Windows.Forms.Label lblRTX_ENCAP_METHOD; + private System.Windows.Forms.ComboBox RTX_ENCAP_METHOD; + private System.Windows.Forms.Label lblRDESTID; + private System.Windows.Forms.Label lblRNODEID; + private System.Windows.Forms.ComboBox RDESTID; + private System.Windows.Forms.ComboBox RNODEID; + private System.Windows.Forms.Label lblRGPO1_1R_COUT; + private System.Windows.Forms.ComboBox RMAVLINK; + private System.Windows.Forms.CheckBox RGPO1_1R_COUT; + private System.Windows.Forms.TextBox RFORMAT; + private System.Windows.Forms.Label lblRGPI1_1R_CIN; + private System.Windows.Forms.CheckBox RGPI1_1R_CIN; + private System.Windows.Forms.ComboBox RSERIAL_SPEED; + private System.Windows.Forms.ComboBox RAIR_SPEED; + private System.Windows.Forms.ComboBox RNETID; + private System.Windows.Forms.Label lblROPPRESEND; + private System.Windows.Forms.ComboBox RTXPOWER; + private System.Windows.Forms.Label lblRMAVLINK; + private System.Windows.Forms.CheckBox RECC; + private System.Windows.Forms.Label lblRECC; + private System.Windows.Forms.Label lblRTXPOWER; + private System.Windows.Forms.CheckBox ROPPRESEND; + private System.Windows.Forms.Label lblRNETID; + private System.Windows.Forms.Label label32; + private System.Windows.Forms.Label label30; + private System.Windows.Forms.Label label31; + private System.Windows.Forms.Label lblRANT_MODE; + private System.Windows.Forms.ComboBox RANT_MODE; + private System.Windows.Forms.Label lblRSER_BRK_DETMS; + private System.Windows.Forms.Label lblRGLOBAL_RETRIES; + private System.Windows.Forms.Label lblRMAX_RETRIES; + private System.Windows.Forms.ComboBox RSER_BRK_DETMS; + private System.Windows.Forms.ComboBox RGLOBAL_RETRIES; + private System.Windows.Forms.ComboBox RMAX_RETRIES; + private System.Windows.Forms.ComboBox RMAX_DATA; + private System.Windows.Forms.Label lblRMAX_DATA; + private System.Windows.Forms.Label label38; + private System.Windows.Forms.TextBox RAESKEY; + private System.Windows.Forms.Label lblRENCRYPTION_LEVEL; + private System.Windows.Forms.CheckBox RRTSCTS; + private System.Windows.Forms.Label lblRRTSCTS; + private System.Windows.Forms.Label lblRMAX_WINDOW; + private System.Windows.Forms.ComboBox RMAX_WINDOW; + private System.Windows.Forms.Label lblRMIN_FREQ; + private System.Windows.Forms.ComboBox RMAX_FREQ; + private System.Windows.Forms.ComboBox RNUM_CHANNELS; + private System.Windows.Forms.ComboBox RDUTY_CYCLE; + private System.Windows.Forms.ComboBox RLBT_RSSI; + private System.Windows.Forms.ComboBox RMIN_FREQ; + private System.Windows.Forms.Label lblRMAX_FREQ; + private System.Windows.Forms.Label lblRNUM_CHANNELS; + private System.Windows.Forms.Label lblRDUTY_CYCLE; + private System.Windows.Forms.Label lblRLBT_RSSI; + private System.Windows.Forms.Button btnRandom; + private System.Windows.Forms.Label lblSBUSIN; + private System.Windows.Forms.CheckBox GPO1_3SBUSIN; + private System.Windows.Forms.Label lblSBUSOUT; + private System.Windows.Forms.Label label45; + private System.Windows.Forms.ComboBox RATE_FREQBAND; + private System.Windows.Forms.Label label46; + private System.Windows.Forms.ComboBox RRATE_FREQBAND; + private System.Windows.Forms.Label lblRSBUSOUT; + private System.Windows.Forms.Label lblRSBUSIN; + private System.Windows.Forms.CheckBox RGPO1_3SBUSIN; + private System.Windows.Forms.TextBox txtCountry; + private System.Windows.Forms.Label label49; + private System.Windows.Forms.Label label50; + private System.Windows.Forms.TextBox txtRCountry; + private Controls.MyButton BUT_SetPPMFailSafeRemote; + private System.Windows.Forms.ComboBox GPO1_3SBUSOUT; + private System.Windows.Forms.ComboBox RGPO1_3SBUSOUT; + private System.Windows.Forms.CheckBox GPO1_0TXEN485; + private System.Windows.Forms.Label lblGPO1_0TXEN485; + private System.Windows.Forms.CheckBox GPO1_3STATLED; + private System.Windows.Forms.Label lblGPO1_3STATLED; + private System.Windows.Forms.CheckBox RGPO1_0TXEN485; + private System.Windows.Forms.Label lblRGPO1_0TXEN485; + private System.Windows.Forms.CheckBox RGPO1_3STATLED; + private System.Windows.Forms.Label lblRGPO1_3STATLED; + private System.Windows.Forms.ComboBox ENCRYPTION_LEVEL; + private System.Windows.Forms.ComboBox RENCRYPTION_LEVEL; + private System.Windows.Forms.Label lblGPIO1_1FUNC; + private System.Windows.Forms.ComboBox GPIO1_1FUNC; + private System.Windows.Forms.Label lblRGPIO1_1FUNC; + private System.Windows.Forms.ComboBox RGPIO1_1FUNC; + private System.Windows.Forms.CheckBox GPO1_3AUXOUT; + private System.Windows.Forms.Label lblGPO1_3AUXOUT; + private System.Windows.Forms.CheckBox GPI1_2AUXIN; + private System.Windows.Forms.Label lblGPI1_2AUXIN; + private System.Windows.Forms.Label label54; + private System.Windows.Forms.ComboBox FSFRAMELOSS; + private System.Windows.Forms.Label lblRFSFRAMELOSS; + private System.Windows.Forms.ComboBox RFSFRAMELOSS; + private System.Windows.Forms.CheckBox RGPO1_3AUXOUT; + private System.Windows.Forms.Label lblRGPO1_3AUXOUT; + private System.Windows.Forms.CheckBox RGPI1_2AUXIN; + private System.Windows.Forms.Label lblRGPI1_2AUXIN; + private Controls.MyButton btnSaveToFile; + private System.Windows.Forms.SaveFileDialog dlgSave; + private Controls.MyButton btnRemoteSaveToFile; + private Controls.MyButton btnLoadFromFile; + private System.Windows.Forms.OpenFileDialog dlgOpen; + private Controls.MyButton btnRemoteLoadFromFile; + } } \ No newline at end of file diff --git a/Radio/Sikradio.cs b/Radio/Sikradio.cs index 688fb4d8a6..e4d5b04610 100644 --- a/Radio/Sikradio.cs +++ b/Radio/Sikradio.cs @@ -1,6 +1,3 @@ -using log4net; -using MissionPlanner.Comms; -using MissionPlanner.Utilities; using System; using System.Collections.Generic; using System.Globalization; @@ -11,6 +8,13 @@ using System.Text.RegularExpressions; using System.Threading; using System.Windows.Forms; +using log4net; +using MissionPlanner.Comms; +using MissionPlanner.Controls; +using MissionPlanner.MsgBox; +using MissionPlanner.Radio; +using MissionPlanner.Utilities; +using Microsoft.VisualBasic; namespace MissionPlanner.Radio { @@ -20,23 +24,32 @@ public partial class Sikradio : UserControl, SikRadio.ISikRadioForm public delegate void ProgressEventHandler(double completed); - /// - /// An alternative function for getting the serial port. Can be left as null - /// if no alternative. - /// - public Func GetCommsSerialAlt; - private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); private bool beta; - private readonly string firmwarefile = Path.GetTempFileName(); + private string firmwarefile = Path.GetTempFileName(); private Dictionary _DefaultLocalEnabled = new Dictionary(); private Dictionary _DefaultCBObjects = new Dictionary(); RFD.RFD900.TSession _Session; ExtraParamControlsSet _LocalExtraParams; ExtraParamControlsSet _RemoteExtraParams; + RFDLib.GUI.Settings.TDynamicLabelEditorPairRegister _DynamicLabelEditorPairRegister; + + RFDLib.GUI.Settings.TLabelEditorPairRegister _LocalLabelEditorPairs = new RFDLib.GUI.Settings.TLabelEditorPairRegister(); + RFDLib.GUI.Settings.TLabelEditorPairRegister _RemoteLabelEditorPairs = new RFDLib.GUI.Settings.TLabelEditorPairRegister(); + Dictionary _KnownNameDescriptions = new Dictionary() + { + {"RSSI_IN_DBM", "RSSI in dBm"}, + {"AUXSER_SPEED", "Aux Baud"}, + {"AIR_FRAMELEN", "Air Frame Length"}, + }; + + RFD.RFD900.TSettings _LocalSettings, _RemoteSettings; + + public event Action DoDisconnectReconnect; + /* ATI5 S0: FORMAT=25 @@ -67,17 +80,15 @@ public Sikradio() _LocalExtraParams = new ExtraParamControlsSet(lblNODEID, NODEID, lblDESTID, DESTID, lblTX_ENCAP_METHOD, TX_ENCAP_METHOD, lblRX_ENCAP_METHOD, RX_ENCAP_METHOD, - lblMAX_DATA, MAX_DATA, - new Control[] {lblMAX_RETRIES, MAX_RETRIES, - lblGLOBAL_RETRIES, GLOBAL_RETRIES, lblSER_BRK_DETMS, SER_BRK_DETMS, - lblANT_MODE, ANT_MODE}, false); + lblMAX_DATA, MAX_DATA, lblMAX_RETRIES, MAX_RETRIES, + new Control[] { + lblGLOBAL_RETRIES, GLOBAL_RETRIES, lblSER_BRK_DETMS, SER_BRK_DETMS}, false); _RemoteExtraParams = new ExtraParamControlsSet(lblRNODEID, RNODEID, lblRDESTID, RDESTID, lblRTX_ENCAP_METHOD, RTX_ENCAP_METHOD, lblRRX_ENCAP_METHOD, RRX_ENCAP_METHOD, - lblRMAX_DATA, RMAX_DATA, - new Control[] {lblRMAX_RETRIES, RMAX_RETRIES, - lblRGLOBAL_RETRIES, RGLOBAL_RETRIES, lblRSER_BRK_DETMS, RSER_BRK_DETMS, - lblRANT_MODE, RANT_MODE}, true); + lblRMAX_DATA, RMAX_DATA, lblRMAX_RETRIES, RMAX_RETRIES, + new Control[] { + lblRGLOBAL_RETRIES, RGLOBAL_RETRIES, lblRSER_BRK_DETMS, RSER_BRK_DETMS}, true); // setup netid NETID.DataSource = Enumerable.Range(0, 500).ToArray(); @@ -117,9 +128,148 @@ public Sikradio() SaveDefaultCBObjects(MAX_WINDOW); SaveDefaultCBObjects(RMAX_WINDOW); + RFDLib.GUI.Settings.TDynamicLabelEditorPair SBUSIN = new RFDLib.GUI.Settings.TDynamicLabelEditorPair(lblSBUSIN, GPO1_3SBUSIN, + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair[] + { + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("GPO1_3SBUSIN", "GPO1_3SBUSIN"), + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("GPO1_1SBUSIN", "GPO1_1SBUSIN"), + }); + RFDLib.GUI.Settings.TDynamicLabelEditorPair RSBUSIN = new RFDLib.GUI.Settings.TDynamicLabelEditorPair(lblRSBUSIN, RGPO1_3SBUSIN, + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair[] + { + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("RGPO1_3SBUSIN", "GPO1_3SBUSIN"), + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("RGPO1_1SBUSIN", "GPO1_1SBUSIN"), + }); + RFDLib.GUI.Settings.TDynamicLabelEditorPair SBUSOUT = new RFDLib.GUI.Settings.TDynamicLabelEditorPair(lblSBUSOUT, GPO1_3SBUSOUT, + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair[] + { + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("GPO1_3SBUSOUT", "GPO1_3SBUSOUT"), + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("GPO1_1SBUSOUT", "GPO1_1SBUSOUT"), + }); + RFDLib.GUI.Settings.TDynamicLabelEditorPair RSBUSOUT = new RFDLib.GUI.Settings.TDynamicLabelEditorPair(lblRSBUSOUT, RGPO1_3SBUSOUT, + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair[] + { + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("RGPO1_3SBUSOUT", "GPO1_3SBUSOUT"), + new RFDLib.GUI.Settings.TDynamicLabelEditorPair.TSettingNameLabelTextPair("RGPO1_1SBUSOUT", "GPO1_1SBUSOUT"), + }); + _DynamicLabelEditorPairRegister = new RFDLib.GUI.Settings.TDynamicLabelEditorPairRegister(new RFDLib.GUI.Settings.TDynamicLabelEditorPair[] + { + SBUSIN, RSBUSIN, SBUSOUT, RSBUSOUT, + }); + + _LocalLabelEditorPairs.Add(lblNODEID, NODEID, toolTip1); + _LocalLabelEditorPairs.Add(lblDESTID, DESTID, toolTip1); + _LocalLabelEditorPairs.Add(lblTX_ENCAP_METHOD, TX_ENCAP_METHOD, toolTip1); + _LocalLabelEditorPairs.Add(lblRX_ENCAP_METHOD, RX_ENCAP_METHOD, toolTip1); + _LocalLabelEditorPairs.Add(lblMAX_DATA, MAX_DATA, toolTip1); + _LocalLabelEditorPairs.Add(lblMAX_RETRIES, MAX_RETRIES, toolTip1); + _LocalLabelEditorPairs.Add(lblGLOBAL_RETRIES, GLOBAL_RETRIES, toolTip1); + _LocalLabelEditorPairs.Add(lblSER_BRK_DETMS, SER_BRK_DETMS, toolTip1); + _LocalLabelEditorPairs.Add(label54, FSFRAMELOSS, toolTip1); + _LocalLabelEditorPairs.Add(lblNETID, NETID, toolTip1); + _LocalLabelEditorPairs.Add(lblTXPOWER, TXPOWER, toolTip1); + _LocalLabelEditorPairs.Add(lblECC, ECC, toolTip1); + _LocalLabelEditorPairs.Add(lblMAVLINK, MAVLINK, toolTip1); + _LocalLabelEditorPairs.Add(lblOPPRESEND, OPPRESEND, toolTip1); + _LocalLabelEditorPairs.Add(lblGPI1_1R_CIN, GPI1_1R_CIN, toolTip1); + _LocalLabelEditorPairs.Add(lblGPO1_1R_COUT, GPO1_1R_COUT, toolTip1); + _LocalLabelEditorPairs.Add(lblGPO1_3STATLED, GPO1_3STATLED, toolTip1); + _LocalLabelEditorPairs.Add(lblGPI1_2AUXIN, GPI1_2AUXIN, toolTip1); + _LocalLabelEditorPairs.Add(lblGPO1_3AUXOUT, GPO1_3AUXOUT, toolTip1); + _LocalLabelEditorPairs.Add(lblMIN_FREQ, MIN_FREQ, toolTip1); + _LocalLabelEditorPairs.Add(lblMAX_FREQ, MAX_FREQ, toolTip1); + _LocalLabelEditorPairs.Add(lblNUM_CHANNELS, NUM_CHANNELS, toolTip1); + _LocalLabelEditorPairs.Add(lblDUTY_CYCLE, DUTY_CYCLE, toolTip1); + _LocalLabelEditorPairs.Add(lblLBT_RSSI, LBT_RSSI, toolTip1); + _LocalLabelEditorPairs.Add(lblRTSCTS, RTSCTS, toolTip1); + _LocalLabelEditorPairs.Add(lblMAX_WINDOW, MAX_WINDOW, toolTip1); + _LocalLabelEditorPairs.Add(lblENCRYPTION_LEVEL, ENCRYPTION_LEVEL, toolTip1); + _LocalLabelEditorPairs.Add(lblGPO1_0TXEN485, GPO1_0TXEN485, toolTip1); + _LocalLabelEditorPairs.Add(lblGPIO1_1FUNC, GPIO1_1FUNC, toolTip1); + + _RemoteLabelEditorPairs.Add(lblRNODEID, RNODEID, toolTip1); + _RemoteLabelEditorPairs.Add(lblRDESTID, RDESTID, toolTip1); + _RemoteLabelEditorPairs.Add(lblRTX_ENCAP_METHOD, RTX_ENCAP_METHOD, toolTip1); + _RemoteLabelEditorPairs.Add(lblRRX_ENCAP_METHOD, RRX_ENCAP_METHOD, toolTip1); + _RemoteLabelEditorPairs.Add(lblRMAX_DATA, RMAX_DATA, toolTip1); + _RemoteLabelEditorPairs.Add(lblRMAX_RETRIES, RMAX_RETRIES, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGLOBAL_RETRIES, RGLOBAL_RETRIES, toolTip1); + _RemoteLabelEditorPairs.Add(lblRSER_BRK_DETMS, RSER_BRK_DETMS, toolTip1); + _RemoteLabelEditorPairs.Add(lblRFSFRAMELOSS, RFSFRAMELOSS, toolTip1); + _RemoteLabelEditorPairs.Add(lblRNETID, RNETID, toolTip1); + _RemoteLabelEditorPairs.Add(lblRTXPOWER, RTXPOWER, toolTip1); + _RemoteLabelEditorPairs.Add(lblRECC, RECC, toolTip1); + _RemoteLabelEditorPairs.Add(lblRMAVLINK, RMAVLINK, toolTip1); + _RemoteLabelEditorPairs.Add(lblROPPRESEND, ROPPRESEND, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPI1_1R_CIN, RGPI1_1R_CIN, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPO1_1R_COUT, RGPO1_1R_COUT, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPO1_3STATLED, RGPO1_3STATLED, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPI1_2AUXIN, RGPI1_2AUXIN, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPO1_3AUXOUT, RGPO1_3AUXOUT, toolTip1); + _RemoteLabelEditorPairs.Add(lblRMIN_FREQ, RMIN_FREQ, toolTip1); + _RemoteLabelEditorPairs.Add(lblRMAX_FREQ, RMAX_FREQ, toolTip1); + _RemoteLabelEditorPairs.Add(lblRNUM_CHANNELS, RNUM_CHANNELS, toolTip1); + _RemoteLabelEditorPairs.Add(lblRDUTY_CYCLE, RDUTY_CYCLE, toolTip1); + _RemoteLabelEditorPairs.Add(lblRLBT_RSSI, RLBT_RSSI, toolTip1); + _RemoteLabelEditorPairs.Add(lblRRTSCTS, RRTSCTS, toolTip1); + _RemoteLabelEditorPairs.Add(lblRMAX_WINDOW, RMAX_WINDOW, toolTip1); + _RemoteLabelEditorPairs.Add(lblRENCRYPTION_LEVEL, RENCRYPTION_LEVEL, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPO1_0TXEN485, RGPO1_0TXEN485, toolTip1); + _RemoteLabelEditorPairs.Add(lblRGPIO1_1FUNC, RGPIO1_1FUNC, toolTip1); + this.Disposed += DisposedEvtHdlr; } + static void getTelemPortWithRadio(ref ICommsSerial comPort) + { + // try telem1 + + comPort = new MAVLinkSerialPort(MainV2.comPort, (int)MAVLink.SERIAL_CONTROL_DEV.TELEM1); + + comPort.ReadTimeout = 4000; + + comPort.Open(); + } + + public static bool Connect(ref ICommsSerial Port) + { + try + { + if (MainV2.comPort.BaseStream.PortName.Contains("TCP")) + { + Port = new TcpSerial(); + Port.BaudRate = MainV2.comPort.BaseStream.BaudRate; + Port.ReadTimeout = 4000; + Port.Open(); + } + else + { + Port = new SerialPort(); + + if (MainV2.comPort.BaseStream.IsOpen) + { + getTelemPortWithRadio(ref Port); + } + else + { + Port.PortName = MainV2.comPort.BaseStream.PortName; + Port.BaudRate = MainV2.comPort.BaseStream.BaudRate; + } + + Port.ReadTimeout = 4000; + + Port.Open(); + } + + return true; + } + catch + { + return false; + } + } + + public void Connect() { var S = GetSession(); @@ -128,11 +278,12 @@ public void Connect() public void Disconnect() { var S = _Session; - if (S != null) + if ((S != null) && S.Port.IsOpen) { S.PutIntoTransparentMode(); } EndSession(); + MissionPlanner.Radio.ComPort.FinishedWithComPortForSiKRadio(); } void DisposedEvtHdlr(object sender, EventArgs e) @@ -178,63 +329,56 @@ private void RestoreAllDefaultCBObjects() } } - private bool getFirmware(Uploader.Board device, bool custom = false) + private bool getFirmware(Uploader.Board device, RFD.RFD900.RFD900 RFD900, bool custom = false) { if (custom) { - return getFirmwareLocal(device == Uploader.Board.DEVICE_ID_RFD900X); + return getFirmwareLocal(RFD900); } + + firmwarefile = Path.GetTempFileName(); - if (device == Uploader.Board.DEVICE_ID_HB1060) - { - if (beta) - { - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/beta/radio~hb1060.ihx", firmwarefile); - } - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/stable/radio~hb1060.ihx", - firmwarefile); - } if (device == Uploader.Board.DEVICE_ID_HM_TRP) { if (beta) { - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/beta/radio~hm_trp.ihx", firmwarefile); + return Download.getFilefromNet("http://firmware.ardupilot.org/SiK/beta/radio~hm_trp.ihx", firmwarefile); } - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/stable/radio~hm_trp.ihx", + return Download.getFilefromNet("http://firmware.ardupilot.org/SiK/stable/radio~hm_trp.ihx", firmwarefile); } if (device == Uploader.Board.DEVICE_ID_RFD900) { if (beta) { - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/beta/radio~rfd900.ihx", firmwarefile); + return Download.getFilefromNet("http://firmware.ardupilot.org/SiK/beta/radio~rfd900.ihx", firmwarefile); } - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/stable/radio~rfd900.ihx", firmwarefile); + return Download.getFilefromNet("http://firmware.ardupilot.org/SiK/stable/radio~rfd900.ihx", firmwarefile); } if (device == Uploader.Board.DEVICE_ID_RFD900A) { if (beta) { - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/beta/radio~rfd900a.ihx", + return Download.getFilefromNet("http://firmware.ardupilot.org/SiK/beta/radio~rfd900a.ihx", firmwarefile); } - return Download.getFilefromNet("https://firmware.ardupilot.org/SiK/stable/radio~rfd900a.ihx", firmwarefile); + return Download.getFilefromNet("http://firmware.ardupilot.org/SiK/stable/radio~rfd900a.ihx", firmwarefile); } if (device == Uploader.Board.DEVICE_ID_RFD900U) { if (beta) { - return Download.getFilefromNet("https://files.rfdesign.com.au/Files/firmware/MPSiK%20V2.6%20rfd900u.ihx", firmwarefile); + return Download.getFilefromNet("http://files.rfdesign.com.au/Files/firmware/MPSiK%20V2.6%20rfd900u.ihx", firmwarefile); } - return Download.getFilefromNet("https://files.rfdesign.com.au/Files/firmware/RFDSiK%20V1.9%20rfd900u.ihx", firmwarefile); + return Download.getFilefromNet("http://files.rfdesign.com.au/Files/firmware/RFDSiK%20V1.9%20rfd900u.ihx", firmwarefile); } if (device == Uploader.Board.DEVICE_ID_RFD900P) { if (beta) { - return Download.getFilefromNet("https://files.rfdesign.com.au/Files/firmware/MPSiK%20V2.6%20rfd900p.ihx", firmwarefile); + return Download.getFilefromNet("http://files.rfdesign.com.au/Files/firmware/MPSiK%20V2.6%20rfd900p.ihx", firmwarefile); } - return Download.getFilefromNet("https://files.rfdesign.com.au/Files/firmware/RFDSiK%20V1.9%20rfd900p.ihx", firmwarefile); + return Download.getFilefromNet("http://files.rfdesign.com.au/Files/firmware/RFDSiK%20V1.9%20rfd900p.ihx", firmwarefile); } if (device == Uploader.Board.DEVICE_ID_RFD900X) { @@ -247,11 +391,22 @@ private bool getFirmware(Uploader.Board device, bool custom = false) /// Loads a local firmware file after prompting user for file. /// /// - private bool getFirmwareLocal(bool Bin) + private bool getFirmwareLocal(RFD.RFD900.RFD900 RFD900) { using (var openFileDialog1 = new OpenFileDialog()) { - openFileDialog1.Filter = Bin ? "Firmware|*.bin" : "Firmware|*.hex;*.ihx"; + string Filter = "Firmware|"; + string[] Exts = RFD900.FirmwareFileNameExtensions; + for (int n = 0; n < Exts.Length; n++) + { + if (n != 0) + { + Filter += ";"; + } + Filter += "*." + Exts[n]; + } + + openFileDialog1.Filter = Filter; openFileDialog1.RestoreDirectory = true; openFileDialog1.Multiselect = false; @@ -259,7 +414,8 @@ private bool getFirmwareLocal(bool Bin) { try { - File.Copy(openFileDialog1.FileName, firmwarefile, true); + firmwarefile = openFileDialog1.FileName; + //File.Copy(openFileDialog1.FileName, firmwarefile, true); } catch (Exception ex) { @@ -291,76 +447,6 @@ private void Sleep(int mstimeout, ICommsSerial comPort = null) } } - /// - /// Tries to upload firmware to the modem using xmodem mode (after prompting user for file) - /// - /// - /// - bool upload_xmodem(ICommsSerial comPort) - { - // try xmodem mode - // xmodem - short cts to ground - try - { - uploader_LogEvent("Trying XModem Mode"); - //comPort.BaudRate = 57600; - comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate; - comPort.ReadTimeout = 1000; - - Thread.Sleep(2000); - var tempd = comPort.ReadExisting(); - Console.WriteLine(tempd); - comPort.Write("U"); - Thread.Sleep(1000); - var resp1 = Serial_ReadLine(comPort); // echo - var resp2 = Serial_ReadLine(comPort); // echo 2 - var tempd2 = comPort.ReadExisting(); // posibly bootloader info / use to sync - // identify - comPort.Write("i"); - // responce is rfd900.... - var resp3 = Serial_ReadLine(comPort); //echo - var resp4 = Serial_ReadLine(comPort); // newline - var resp5 = Serial_ReadLine(comPort); // bootloader info - uploader_LogEvent(resp5); - if (resp5.Contains("RFD900")) - { - // start upload - comPort.Write("u"); - var resp6 = Serial_ReadLine(comPort); // echo - var resp7 = Serial_ReadLine(comPort); // Ready - if (resp7.Contains("Ready")) - { - comPort.ReadTimeout = 3500; - // responce is C - var isC = comPort.ReadByte(); - var temp = comPort.ReadExisting(); - if (isC == 'C') - { - if (getFirmwareLocal(false)) - { - - XModem.LogEvent += uploader_LogEvent; - XModem.ProgressEvent += uploader_ProgressEvent; - // start file send - XModem.Upload(firmwarefile, - comPort); - XModem.LogEvent -= uploader_LogEvent; - XModem.ProgressEvent -= uploader_ProgressEvent; - return true; - } - return false; - } - } - } - } - catch (Exception ex2) - { - log.Error(ex2); - } - - return false; - } - private void BUT_upload_Click(object sender, EventArgs e) { ProgramFirmware(false); @@ -370,7 +456,7 @@ private void iHex_ProgressEvent(double completed) { try { - Progressbar.Value = (int)(completed * 100); + Progressbar.Value = (int) (completed*100); Application.DoEvents(); } catch @@ -420,7 +506,7 @@ private void uploader_ProgressEvent(double completed) { try { - Progressbar.Value = (int)Math.Min(completed * 100, 100); + Progressbar.Value = (int)Math.Min (completed*100,100); Application.DoEvents(); } catch @@ -435,305 +521,493 @@ string GetParamNumber(string Part1) return Part1.Substring(S + 1); } - private void BUT_savesettings_Click(object sender, EventArgs e) + int GetValueFromControl(Control control) { - //EndSession(); - var Session = GetSession(); - - if (Session == null) + if (control.GetType() == typeof(CheckBox)) { - return; + return ((CheckBox)control).Checked ? 1 : 0; } + else if (control is ComboBox) + { + string CBValue = GetCBValue((ComboBox)control); - EnableConfigControls(false); - EnableProgrammingControls(false); - lbl_status.Text = "Connecting"; + int Result; - if (Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND) + if (int.TryParse(CBValue, out Result)) + { + return Result; + } + else + { + return 0; + } + } + else { - // cleanup - doCommand(Session.Port, "AT&T", false, 1); + return 0; + } + } - Session.Port.DiscardInBuffer(); + class TBaseSetting + { + } - lbl_status.Text = "Doing Command"; + class TSetting : TBaseSetting + { + public T Value; + public TSetting(T Value) + { + this.Value = Value; + } + } - if (RTI.Text != "") + TBaseSetting GetSettingFromControl(Control control) + { + if (control.GetType() == typeof(CheckBox)) + { + return new TSetting(((CheckBox)control).Checked ? 1 : 0); + } + else if (control is TextBox) + { + return new TSetting(control.Text); + } + else if (control is ComboBox) + { + int x; + + if (int.TryParse(GetCBValue((ComboBox)control), out x)) { - // remote - var answer = doCommand(Session.Port, "RTI5", true); + return new TSetting(x); + } + } - var items = answer.Split(new[] { '\n' }, StringSplitOptions.RemoveEmptyEntries); + return null; + } - foreach (var item in items) + /// + /// Returns whether x is different to y. + /// + /// + /// + /// + bool GetIsDifferent(RFD.RFD900.TBaseSetting x, TBaseSetting y) + { + if (y is TSetting) + { + return x is RFD.RFD900.TSetting && ((RFD.RFD900.TSetting)x).Value != ((TSetting)y).Value; + } + else if (y is TSetting) + { + return x is RFD.RFD900.TTextSetting && ((RFD.RFD900.TTextSetting)x).Text != ((TSetting)y).Value; + } + else + { + return false; + } + } + + /// + /// Make a clone of the given original setting. Update it's value with Value, and return it. + /// + /// The original setting. Must not be null. + /// The new value for the setting. Must not be null. + /// The new cloned setting with updated value. Never null. + RFD.RFD900.TBaseSetting UpdateSetting(RFD.RFD900.TBaseSetting Orig, TBaseSetting Value) + { + if (Value is TSetting) + { + RFD.RFD900.TSetting y = (RFD.RFD900.TSetting)Orig.Clone(); + y.Value = ((TSetting)Value).Value; + return y; + } + else + { + RFD.RFD900.TTextSetting y = (RFD.RFD900.TTextSetting)Orig.Clone(); + y.Text = ((TSetting)Value).Value; + return y; + } + } + + /// + /// Figure out which settings in the GUI have different values to the given original settings. + /// Return a list of the settings which have changed, and their new values. + /// + /// The original settings and their values. Must not be null. + /// The relevant groupbox. Must not be null. + /// true if the remote modem, false if the local modem. + /// + Dictionary GetUpdatedSettingsFromGroupBox( + Dictionary Orig, GroupBox GB, + bool Remote) + { + Dictionary Result = new Dictionary(); + + foreach (var kvp in Orig) + { + var control = FindControlInGroupBox(GB, (Remote ? "R" : "") + kvp.Key); + + if (control != null) + { + var S = GetSettingFromControl(control); + + if (S != null) { - //if (item.StartsWith("S")) + if (GetIsDifferent(kvp.Value, S)) { - int multipoint_fix = -1; - if (item.StartsWith("[")) + Result[kvp.Key] = UpdateSetting(kvp.Value, S); + } + } + } + } + + return Result; + } + + /// + /// Check that the settings in the given groupbox are valid. If invalid, shows a message box listing the issues. + /// + /// + /// Whether it's for the remote modem. + /// The settings read from the modem. Must not be null. + /// true if valid, false if invalid. + bool CheckSettingsValid(GroupBox GB, bool Remote, + Dictionary Orig) + { + var Changed = GetUpdatedSettingsFromGroupBox(Orig, GB, Remote); + + Dictionary NewSettings = new Dictionary(Orig); + RFDLib.Collections.Update(NewSettings, Changed); + + RFD.RFD900.TSettings Settings = new RFD.RFD900.TSettings(NewSettings); + + var Errors = Settings.CheckValid(); + + if (Errors.Length == 0) + { + return true; + } + else + { + string ErrorMsg = Remote ? "Remote" : "Local" + " settings invalid, operation aborted:"; + + foreach (var em in Errors) + { + ErrorMsg += "\n\t" + em; + } + + MsgBox.CustomMessageBox.Show(ErrorMsg); + + return false; + } + } + + /// + /// Save settings from GUI to a modem. + /// + /// The relevant groupbox. Must not be null. + /// true if remote modem, false if local. + /// The serial port to use. Must not be null. + /// The settings read from the modem. These are not modified by this function. Must not be null. + void SaveSettingsFromGroupBox(GroupBox GB, bool Remote, ICommsSerial Port, + Dictionary Orig) + { + var Changed = GetUpdatedSettingsFromGroupBox(Orig, GB, Remote); + string CommandPrefix = Remote ? "R" : "A"; + + foreach (var kvp in Changed) + { + if (!kvp.Key.Contains("FORMAT")) + { + var cmdanswer = doCommand(Port, + CommandPrefix + "T" + kvp.Value.Designator + "=" + kvp.Value.GetValueAsString(), + kvp.Value.Designator.Contains("&E")); + + if (cmdanswer.Contains("OK")) + { + if (kvp.Key.Contains("GPO1_1R_COUT") || + kvp.Key.Contains("GPO1_3SBUSOUT")) + { + if (kvp.Value is RFD.RFD900.TSetting && ((RFD.RFD900.TSetting)kvp.Value).Value == 1) { - multipoint_fix = item.IndexOf(']') + 1; + //Also need to set RTPO. + cmdanswer = doCommand(Port, + CommandPrefix + "TPO=1"); } - var mod_item = item; - if (multipoint_fix > 0 && item.Length > multipoint_fix) + else { - mod_item = item.Substring(multipoint_fix).Trim(); + cmdanswer = doCommand(Port, + CommandPrefix + "TPI=1"); } - var values = mod_item.Split(':', '='); + } + else if (kvp.Key.Contains("GPI1_1R_CIN") || + kvp.Key.Contains("GPO1_3SBUSIN")) + { + //Also need to set RTPI. + cmdanswer = doCommand(Port, + CommandPrefix + "TPI=1"); + } + if (!cmdanswer.Contains("OK")) + { + MsgBox.CustomMessageBox.Show("Set Command error"); + } - if (values.Length == 3) - { - values[1] = values[1].Replace("/", "_"); - - var controls = groupBoxRemote.Controls.Find("R" + values[1].Trim(), true); - - if (controls.Length > 0) - { - if (controls[0].GetType() == typeof(CheckBox)) - { - var value = ((CheckBox)controls[0]).Checked ? "1" : "0"; - - if (value != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "RTS" + values[0].Trim().TrimStart('S') + "=" + value); - - if (cmdanswer.Contains("OK")) - { - } - else - { - if (values[1] == "ENCRYPTION_LEVEL") - { - // set this on the local radio as well. - doCommand(Session.Port, "ATS" + values[0].Trim().TrimStart('S') + "=" + value); - // both radios should now be using the default key - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - } - else if (!controls[0].Name.Contains("FORMAT") && controls[0] is TextBox) - { - if (controls[0].Text != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "RTS" + values[0].Trim().TrimStart('S') + "=" + controls[0].Text); - - if (cmdanswer.Contains("OK")) - { - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - else if (controls[0].Name.Contains("MAVLINK")) // - { - if (((ComboBox)controls[0]).SelectedValue.ToString() != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "RTS" + values[0].Trim().TrimStart('S') + "=" + ((ComboBox) controls[0]).SelectedValue); - - if (cmdanswer.Contains("OK")) - { - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - else if (controls[0] is ComboBox) - { - string CBValue = GetCBValue((ComboBox)controls[0]); - if (CBValue != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "RTS" + values[0].Trim().TrimStart('S') + "=" + CBValue); - - if (cmdanswer.Contains("OK")) - { - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - } - } + } + else + { + if (Remote && (kvp.Key == "ENCRYPTION_LEVEL")) + { + // set this on the local radio as well. + doCommand(Port, "AT" + kvp.Value.Designator + "=" + kvp.Value.GetValueAsString()); + // both radios should now be using the default key + } + else + { + MsgBox.CustomMessageBox.Show("Set Command error"); } } + } + } + } - Sleep(100); + /// + /// Returns whether encryption is enabled, as per the given combo box. + /// + /// The combo box which is used to set encryption level. Must not be null. + /// true if enabled, otherwise false. + bool GetIsEncryptionEnabled(ComboBox CB) + { + return GetEncryptionLevelValue(CB) != 0; + } + + /// + /// Get the max encryption key length in hex numerals. + /// + /// The encryption level setting combo box. Must not be null. + /// The max encryption key length, in hex numerals. + int GetEncryptionMaxKeyLength(ComboBox CB) + { + if (CB.Text.Contains("b")) + { + var Parts = CB.Text.Split('b'); + if (Parts.Length >= 1) + { + int QTYBits; + + if (int.TryParse(Parts[0], out QTYBits)) + { + return QTYBits / 4; + } } - Session.Port.DiscardInBuffer(); + return 0; + } + else + { + if (CB.Text == "0") + { + return 0; + } + else { - //local - string answer = ""; - for (int n = 0; n < 5; n++) + return 32; + } + } + } + + /// + /// Get the encryption level setting number value. + /// + /// The combo box to get number value for. Must not be null. + /// The level setting number value. + int GetEncryptionLevelValue(ComboBox CB) + { + if (CB.Tag != null) + { + RFD.RFD900.TSetting Setting = (RFD.RFD900.TSetting)CB.Tag; + + if (Setting.Options != null) + { + foreach (var O in Setting.Options) { - answer = doCommand(Session.Port, "ATI5", true); - if (answer.Length != 0) + if (O.OptionName == CB.Text) { - break; + return O.Value; } } + } + } + + int Result; + if (int.TryParse(CB.Text, out Result)) + { + return Result; + } + return 0; + } + + private void BUT_savesettings_Click(object sender, EventArgs e) + { + if ( + ( + (RTI.Text == "") || + CheckSettingsValid + ( + groupBoxRemote, true, + RFDLib.Collections.Translate(_RemoteSettings.Settings, (x) => (RFD.RFD900.TBaseSetting)x) + ) + ) + && + CheckSettingsValid + ( + groupBoxLocal, false, + RFDLib.Collections.Translate(_LocalSettings.Settings, (x) => (RFD.RFD900.TBaseSetting)x) + ) + ) + { + + //EndSession(); + var Session = GetSession(); + + if (Session == null) + { + return; + } + + List EnabledControls = new List(); + foreach (Control C in groupBoxLocal.Controls) + { + if (C.Enabled) + { + EnabledControls.Add(C); + } + } + foreach (Control C in groupBoxRemote.Controls) + { + if (C.Enabled) + { + EnabledControls.Add(C); + } + } + + EnableConfigControls(false, false); + EnableProgrammingControls(false); + lbl_status.Text = "Connecting"; + + if (Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND) + { + // cleanup + doCommand(Session.Port, "AT&T", false, 1); + + Session.Port.DiscardInBuffer(); + + lbl_status.Text = "Doing Command"; - var items = answer.Split(new[] { '\n' }, StringSplitOptions.RemoveEmptyEntries); - foreach (var item in items) + if (RTI.Text != "") { - //if (item.StartsWith("S")) - { - var values = item.Split(':', '='); + // remote + var answer = doCommand(Session.Port, "RTI5", true); - if (values.Length == 3) - { - values[1] = values[1].Replace("/", "_"); - - var controls = groupBoxLocal.Controls.Find(values[1].Trim(), true); - - if (controls.Length > 0) - { - if (controls[0].GetType() == typeof(CheckBox)) - { - var value = ((CheckBox)controls[0]).Checked ? "1" : "0"; - - if (value != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "ATS" + GetParamNumber(values[0]) + "=" + value); - - if (cmdanswer.Contains("OK")) - { - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - else if (controls[0] is TextBox) - { - } - else if (controls[0].Name.Contains("MAVLINK")) // - { - if (((ComboBox)controls[0]).SelectedValue.ToString() != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "ATS" + GetParamNumber(values[0]) + "=" + ((ComboBox) controls[0]).SelectedValue); - - if (cmdanswer.Contains("OK")) - { - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - else if (controls[0] is ComboBox) - { - string CBValue = GetCBValue((ComboBox)controls[0]); - if (CBValue != values[2].Trim()) - { - var cmdanswer = doCommand(Session.Port, - "ATS" + GetParamNumber(values[0]) + "=" + CBValue); - - if (cmdanswer.Contains("OK")) - { - } - else - { - MsgBox.CustomMessageBox.Show("Set Command error"); - } - } - } - } - } - } + SaveSettingsFromGroupBox(groupBoxRemote, true, Session.Port, + RFDLib.Collections.Translate(_RemoteSettings.Settings, (x) => (RFD.RFD900.TBaseSetting)x)); + + Sleep(100); } - // set encryption keys at the same time, so if we are enabled we dont lose comms. - // we have set encryption to on for both radios, they will be using the default key atm - if (RENCRYPTION_LEVEL.Checked) + Session.Port.DiscardInBuffer(); { - if (System.Text.RegularExpressions.Regex.IsMatch(txt_Raeskey.Text, @"\A\b[0-9a-fA-F]+\b\Z") - && (txt_Raeskey.Text.Length <= 32)) + //local + string answer = ""; + for (int n = 0; n < 5; n++) { - doCommand(Session.Port, "RT&E=" + txt_Raeskey.Text.PadRight(32, '0'), true); + answer = doCommand(Session.Port, "ATI5", true); + if (answer.Length != 0) + { + break; + } } - else + + SaveSettingsFromGroupBox(groupBoxLocal, false, Session.Port, + RFDLib.Collections.Translate(_LocalSettings.Settings, (x) => (RFD.RFD900.TBaseSetting)x)); + + // set encryption keys at the same time, so if we are enabled we dont lose comms. + // we have set encryption to on for both radios, they will be using the default key atm + if (GetIsEncryptionEnabled(RENCRYPTION_LEVEL)) { - //Complain that encryption key invalid. - lbl_status.Text = "Fail"; - MsgBox.CustomMessageBox.Show("Encryption key not valid hex number <= 32 hex numerals"); + int MaxKeyLength = GetEncryptionMaxKeyLength(RENCRYPTION_LEVEL); + RAESKEY.Text = RAESKEY.Text.Trim(); + + if (System.Text.RegularExpressions.Regex.IsMatch(RAESKEY.Text, @"\A\b[0-9a-fA-F]+\b\Z") + && (RAESKEY.Text.Length <= MaxKeyLength)) + { + doCommand(Session.Port, "RT&E=" + RAESKEY.Text.PadRight(MaxKeyLength, '0'), true); + } + else + { + //Complain that encryption key invalid. + lbl_status.Text = "Fail"; + MsgBox.CustomMessageBox.Show("Encryption key not valid hex number <= " + MaxKeyLength.ToString() + " hex numerals"); + } } - } - if (ENCRYPTION_LEVEL.Checked) - { - if (System.Text.RegularExpressions.Regex.IsMatch(txt_aeskey.Text, @"\A\b[0-9a-fA-F]+\b\Z") - && (txt_aeskey.Text.Length <= 32)) + if (GetIsEncryptionEnabled(ENCRYPTION_LEVEL)) { - doCommand(Session.Port, "AT&E=" + txt_aeskey.Text.PadRight(32, '0'), true); + int MaxKeyLength = GetEncryptionMaxKeyLength(ENCRYPTION_LEVEL); + AESKEY.Text = AESKEY.Text.Trim(); + + if (System.Text.RegularExpressions.Regex.IsMatch(AESKEY.Text, @"\A\b[0-9a-fA-F]+\b\Z") + && (AESKEY.Text.Length <= MaxKeyLength)) + { + doCommand(Session.Port, "AT&E=" + AESKEY.Text.PadRight(MaxKeyLength, '0'), true); + } + else + { + //Complain that encryption key invalid. + lbl_status.Text = "Fail"; + MsgBox.CustomMessageBox.Show("Encryption key not valid hex number <= " + MaxKeyLength.ToString() + " hex numerals"); + } } - else + + + if (RTI.Text != "") { - //Complain that encryption key invalid. - lbl_status.Text = "Fail"; - MsgBox.CustomMessageBox.Show("Encryption key not valid hex number <= 32 hex numerals"); - } - } + // write it + doCommand(Session.Port, "RT&W"); + // return to normal mode + doCommand(Session.Port, "RTZ"); + } - if (RTI.Text != "") - { // write it - doCommand(Session.Port, "RT&W"); + var cmdwriteanswer = doCommand(Session.Port, "AT&W"); + if (!cmdwriteanswer.Contains("OK")) + { + MsgBox.CustomMessageBox.Show("Failed to save parameters"); + } // return to normal mode - doCommand(Session.Port, "RTZ"); - } - - // write it - var cmdwriteanswer = doCommand(Session.Port, "AT&W"); - if (!cmdwriteanswer.Contains("OK")) - { - MsgBox.CustomMessageBox.Show("Failed to save parameters"); + doCommand(Session.Port, "ATZ"); } + lbl_status.Text = "Done"; + EnableConfigControls(true, true); + } + else + { // return to normal mode doCommand(Session.Port, "ATZ"); - } - - lbl_status.Text = "Done"; - } - else - { - // return to normal mode - doCommand(Session.Port, "ATZ"); - lbl_status.Text = "Fail"; - MsgBox.CustomMessageBox.Show("Failed to enter command mode"); - } + lbl_status.Text = "Fail"; + MsgBox.CustomMessageBox.Show("Failed to enter command mode"); + EnableConfigControls(true, false); + } - //Need to do this because modem rebooted. - Session.PutIntoATCommandModeAssumingInTransparentMode(); + //Need to do this because modem rebooted. + Session.PutIntoATCommandModeAssumingInTransparentMode(); - EnableConfigControls(true); - EnableProgrammingControls(true); + EnableProgrammingControls(true); - if (GetCommsSerialAlt == null) - { - EndSessionClosePort(); + UpdateSetPPMFailSafeButtons(); } } @@ -798,23 +1072,29 @@ public static IEnumerable Range(int start, int step, int end) } } - - private bool SetupCBWithSetting(ComboBox CB, Dictionary Settings, - string Value, bool Remote) + private void SetupCBWithDefaultEncryptionOptions(ComboBox CB) { - string SettingName; + CB.Tag = null; + CB.DataSource = Range(0, 1, 1); + CB.Text = "0"; + } - if (Remote) - { - SettingName = CB.Name.Substring(1); - } - else - { - SettingName = CB.Name; - } - if (Settings.ContainsKey(SettingName)) + /// + /// Set the given combo box to use the corresponding setting in the given dictionary of + /// settings. If no corresponding setting exists in that dictionary, just set it to the + /// given value. + /// + /// The combo box. Must not be null. + /// The settings. Must not be null. + /// The string value representation to set it to. Must not be null. + /// true if it is a remote modem setting, false if local. + /// + private bool SetupCBWithSetting(ComboBox CB, Dictionary Settings, + string Value, bool Remote, string SettingName) + { + if (Settings.ContainsKey(SettingName) && Settings[SettingName] is RFD.RFD900.TSetting) { - var Setting = Settings[SettingName]; + var Setting = (RFD.RFD900.TSetting)Settings[SettingName]; if (Setting.Options != null) { //Use options. @@ -826,7 +1106,7 @@ private bool SetupCBWithSetting(ComboBox CB, Dictionary dict; + if (Simple) + { + dict = Enum.GetValues(typeof(mavlink_option_simple)) + .Cast() + .ToDictionary(t => (int)t, t => t.ToString()); + } + else + { + dict = Enum.GetValues(typeof(mavlink_option)) + .Cast() + .ToDictionary(t => (int)t, t => t.ToString()); + } + + CB.DataSource = dict.ToArray(); + } + + /// + /// Given an array of lines returned from ATI5 command from a modem, + /// remove the "[n]" from the start of the lines. The "[n]" is returned + /// from a modem at the start of the lines if it is running multipoint firmware. + /// + /// The raw lines returned from the modem. Must not be null. + /// The character index into the string immediately after + /// the initial "[n]", or -1 if not multipoint. + /// The modified lines. Never null. + string[] ModifyReturnedStringsForMultipoint(string[] items, int multipoint_fix) + { + string[] Result = new string[items.Length]; + + for (int n = 0; n < items.Length; n++) + { + Result[n] = items[n]; + if (multipoint_fix > 0 && items[n].Length > multipoint_fix) + { + Result[n] = items[n].Substring(multipoint_fix).Trim(); + } + } + + return Result; + } + + Control FindControlInGroupBox(GroupBox GB, string Name) + { + Control Result = _DynamicLabelEditorPairRegister.FindAndSetUpEditorWithSettingName(Name); + if (Result == null) + { + var Array = GB.Controls.Find(Name, true); + + if (Array.Length == 0) + { + return null; + } + else + { + return Array[0]; + } + } + else + { + return Result; + } + } + + /// + /// Returns whether it can be determined that the setting (from the given Settings) with the given + /// SettingName only has one value/option available (i.e. setting can't be changed). + /// + /// The dictionary of settings for the modem. Must not be null. + /// The setting name. Must not be null. + /// Returns true if it can be determined that the setting can only have one value, otherwise false. + bool GetDoesCheckboxHaveOnlyOneOption(Dictionary Settings, string SettingName) + { + if (Settings.ContainsKey(SettingName)) + { + var BaseSetting = Settings[SettingName]; + + if (BaseSetting is RFD.RFD900.TSetting) + { + RFD.RFD900.TSetting Setting = (RFD.RFD900.TSetting)BaseSetting; + + if (Setting.Options != null) + { + if (Setting.Options.Length == 1) + { + return true; + } + } + if (Setting.Range != null) + { + if (Setting.Range.GetOptions().Length == 1) + { + return true; + } + } + } + } + + return false; + } + + /// + /// Configure and return a spare editor if one is available. + /// + /// The name of the setting to get the editor for. Must not be null. + /// The setting to get the editor for. Must not be null. + /// Whether it is the remote set of settings. + /// A control to use, or null if none available. + Control GetSpareEditor(string ThisSetting, RFD.RFD900.TSetting Setting, bool Remote) + { + RFDLib.GUI.Settings.TLabelEditorPairRegister Reg = Remote ? _RemoteLabelEditorPairs : _LocalLabelEditorPairs; + Control Result = null; + string Description = Remote ? ThisSetting.Substring(1) : ThisSetting; + + if (_KnownNameDescriptions.ContainsKey(Description)) + { + Description = _KnownNameDescriptions[Description]; + } + + if (Setting.GetIsFlag()) + { + Result = Reg.GetSpareCheckbox(ThisSetting, Description); + } + + if (Result == null) + { + Result = Reg.GetSpareComboBox(ThisSetting, Description); + } + + return Result; + } + + /// + /// Update the given setting control with the given setting value + /// + /// The control to update. Must not be null. + /// All of the settings read from the modem. Must not be null. + /// The name of the setting the control is for. Must not be null. + /// The setting value as text. Must not be null. + /// true if remote modem, false if local modem. + /// true if failed, false if successful. + bool UpdateControlWithValue(Control control, + Dictionary Settings, + string SettingName, + string Value, + bool Remote) + { + bool SomeSettingsInvalid = false; + control.Parent.Enabled = true; + control.Enabled = true; + + if (control is CheckBox) + { + ((CheckBox)control).Checked = Value == "1"; + //If the setting can only have one option/value... + if (GetDoesCheckboxHaveOnlyOneOption(Settings, SettingName)) + { + //Disable the control + control.Enabled = false; + } + } + else if (control is TextBox) + { + ((TextBox)control).Text = Value; + } + else if (Settings.ContainsKey(SettingName) && Settings[SettingName] is RFD.RFD900.TSetting) + { + if (control.Name.Contains("MAVLINK") && + !(Settings.ContainsKey("MAVLINK") && + (Settings["MAVLINK"] is RFD.RFD900.TSetting && + ((RFD.RFD900.TSetting)Settings["MAVLINK"]).Options != null))) // + { + var ans = Enum.Parse(typeof(mavlink_option), Value); + ((ComboBox)control).Text = ans.ToString(); + } + else if (control is ComboBox) + { + if (!SetupCBWithSetting((ComboBox)control, Settings, + Value, Remote, SettingName)) + { + ((ComboBox)control).Text = Value; + if (((ComboBox)control).Text != Value) + { + SomeSettingsInvalid = true; + } + } + } + } + + return SomeSettingsInvalid; + } + + /// + /// Update the settings controls in the given groupbox with the given set of settings. + /// + /// The group box. Must not be null. + /// true if it is for the remote modem, false if for the local modem. + /// The settings. Must not be null. + void UpdateControlsWithValues(GroupBox GB, bool Remote, Dictionary Settings) + { + foreach (var kvp in Settings) + { + string EditorName = (Remote ? "R" : "") + kvp.Key; + + var control = FindControlInGroupBox(GB, EditorName); + + if (control != null) + { + UpdateControlWithValue(control, Settings, EditorName, kvp.Value.GetValueAsString(), Remote); + } + } + } + + /// + /// Given a groupbox containing a set of controls, load them with the given values and settings. + /// + /// The groupbox. Must not be null. + /// true if it is the remote groupbox, false if it is the local groupbox. + /// The lines returned by ATI5 command. Must not be null. + /// The settings parsed from the modem. Must not be null. + /// true if at least one setting had an invalid value, otherwise false. + bool SetUpControlsWithValues(GroupBox GB, bool Remote, string[] items, Dictionary Settings) + { + /*RFD900Tools.GUI.frmCfgTest frm = new RFD900Tools.GUI.frmCfgTest(); + RFD900Tools.GUI.TConfig Cfg = new RFD900Tools.GUI.TConfig(frm.GetControl()); + Cfg.Update(Settings, items); + frm.Show();*/ + + _LocalLabelEditorPairs.SetUp(new List(Settings.Keys)); + _RemoteLabelEditorPairs.SetUp(new List( + RFDLib.Array.CherryPickArray(Settings.Keys.ToArray(), + (n) => "R" + n))); + + bool SomeSettingsInvalid = false; + + foreach (var item in items) + { + var values = item.Split(new char[] { ':', '=' }, StringSplitOptions.RemoveEmptyEntries); + + if (item.Contains("ANT_MODE")) + { + System.Diagnostics.Debug.WriteLine("Ant mode"); + } + + if (values.Length == 3) + { + string SettingName = values[1].Trim(); + string EditorName = values[1].Replace("/", "_").Trim(); + + var control = FindControlInGroupBox(GB, (Remote ? "R" : "") + EditorName); + + if (control == null) + { + if (Settings.ContainsKey(SettingName) && Settings[SettingName] is RFD.RFD900.TSetting) + { + var Setting = (RFD.RFD900.TSetting)Settings[SettingName]; + if (Setting.Range != null || Setting.Options != null) + { + control = GetSpareEditor((Remote ? "R" : "") + EditorName, Setting, Remote); + } + } + } + + if (control != null) + { + GB.Enabled = true; + SomeSettingsInvalid |= UpdateControlWithValue(control, + RFDLib.Collections.Translate(Settings, (x) => (RFD.RFD900.TBaseSetting)x), + SettingName, values[2].Trim(), Remote); + } + } + else + { + log.Info("Odd config line :" + item); + } + } + + return SomeSettingsInvalid; } - void SetupComboForMavlink(ComboBox CB, bool Simple) + /// + /// Get the country code from the modem as a string, or "--" if unknown or not locked to country. + /// + /// The session. Must not be null. + /// The function to get the country code, given the modem object. Must not be null. + /// The country code string. + string GetCountryCodeFromSession(RFD.RFD900.TSession Session, + Func GetCC) { - Dictionary dict; - if (Simple) + RFD.RFD900.RFD900xux.TCountry CC; + var Mdm = Session.GetModemObject(); + + if (Mdm == null || !(Mdm is RFD.RFD900.RFD900xuxRevN) || + !RFD.RFD900.RFD900xux.GetIsCountryLocked(CC = GetCC((RFD.RFD900.RFD900xuxRevN)Mdm))) { - dict = Enum.GetValues(typeof(mavlink_option_simple)) - .Cast() - .ToDictionary(t => (int)t, t => t.ToString()); + return "--"; } else { - dict = Enum.GetValues(typeof(mavlink_option)) - .Cast() - .ToDictionary(t => (int)t, t => t.ToString()); + return CC.ToString(); } - - CB.DataSource = dict.ToArray(); } /// @@ -888,6 +1466,8 @@ void SetupComboForMavlink(ComboBox CB, bool Simple) /// private void BUT_getcurrent_Click(object sender, EventArgs e) { + //System.Diagnostics.Stopwatch SW = new System.Diagnostics.Stopwatch(); + //SW.Start(); //EndSession(); var Session = GetSession(); @@ -896,38 +1476,62 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) return; } + _AlreadyInEncCheckChangedEvtHdlr = true; + ResetAllControls(groupBoxLocal); ResetAllControls(groupBoxRemote); + SetupCBWithDefaultEncryptionOptions(ENCRYPTION_LEVEL); + SetupCBWithDefaultEncryptionOptions(RENCRYPTION_LEVEL); - EnableConfigControls(false); + EnableConfigControls(false, false); EnableProgrammingControls(false); lbl_status.Text = "Connecting"; + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Putting into AT CMD mode"); + try { if (Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND) { + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done putting into AT CMD mode"); + bool SomeSettingsInvalid = false; // cleanup doCommand(Session.Port, "AT&T", false, 1); + /*Session.ATCClient.Timeout = 100; + Session.ATCClient.DoCommand("AT&T"); + Session.ATCClient.Timeout = 1000;*/ + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done AT&T cmd"); Session.Port.DiscardInBuffer(); lbl_status.Text = "Doing Command ATI & RTI"; //Set the text box to show the radio version - int multipoint_fix = -1; - var ati_str = doCommand(Session.Port, "ATI").Trim(); + int multipoint_fix = -1; //If this radio has multipoint firmware, the index within returned strings to use for returned values, otherwise -1. + var ati_str = doCommand(Session.Port, "ATI").Trim(); //Session.ATCClient.DoQuery("ATI", true);// doCommand(Session.Port, "ATI").Trim(); + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done ATI cmd"); + if (ati_str.StartsWith("[")) { multipoint_fix = ati_str.IndexOf(']') + 1; } ATI.Text = ati_str; + string LocalFWVer = RFD.RFD900.RFD900.ATIResponseToFWVersion(ati_str); + NumberStyles style = NumberStyles.Any; //Get the board frequency. - var freqstring = doCommand(Session.Port, "ATI3").Trim(); + var freqstring = doCommand(Session.Port, "ATI3").Trim(); //Session.ATCClient.DoQuery("ATI3", true);// doCommand(Session.Port, "ATI3").Trim(); + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done ATI3 cmd"); + + //Some multipoint firmware versions don't reply to ATI command with [n] at start of reply, but they do for ATI3 command, so check for [n] again... + if (multipoint_fix < 0 && freqstring.StartsWith("[")) + { + multipoint_fix = freqstring.IndexOf(']') + 1; + } + if (multipoint_fix > 0) { freqstring = freqstring.Substring(multipoint_fix).Trim(); @@ -938,15 +1542,16 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) var freq = (Uploader.Frequency) - Enum.Parse(typeof(Uploader.Frequency), - int.Parse(freqstring.ToLower().Replace("x", ""), style, CultureInfo.InvariantCulture) - .ToString()); + Enum.Parse(typeof (Uploader.Frequency), + int.Parse(freqstring.ToLower().Replace("x", ""), style).ToString()); ATI3.Text = freq.ToString(); style = NumberStyles.Any; - var boardstring = doCommand(Session.Port, "ATI2").Trim(); + var boardstring = doCommand(Session.Port, "ATI2").Trim(); //Session.ATCClient.DoQuery("ATI2", true);// doCommand(Session.Port, "ATI2").Trim(); + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done ATI2 cmd"); + if (multipoint_fix > 0) { boardstring = boardstring.Substring(multipoint_fix).Trim(); @@ -957,8 +1562,11 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) Session.Board = (Uploader.Board) - Enum.Parse(typeof(Uploader.Board), - int.Parse(boardstring.ToLower().Replace("x", ""), style, CultureInfo.InvariantCulture).ToString()); + Enum.Parse(typeof (Uploader.Board), + int.Parse(boardstring.ToLower().Replace("x", ""), style).ToString()); + + txtCountry.Text = GetCountryCodeFromSession(Session, + (m) => m.GetCountryCode()); ATI2.Text = Session.Board.ToString(); @@ -1003,19 +1611,19 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) // 8 and 9 if (freq == Uploader.Frequency.FREQ_915) { - MIN_FREQ.DataSource = Range(895000, 1000, 935000); - RMIN_FREQ.DataSource = Range(895000, 1000, 935000); + MIN_FREQ.DataSource = Range(902000, 1000, 927000); + RMIN_FREQ.DataSource = Range(902000, 1000, 927000); - MAX_FREQ.DataSource = Range(895000, 1000, 935000); - RMAX_FREQ.DataSource = Range(895000, 1000, 935000); + MAX_FREQ.DataSource = Range(903000, 1000, 928000); + RMAX_FREQ.DataSource = Range(903000, 1000, 928000); } else if (freq == Uploader.Frequency.FREQ_433) { - MIN_FREQ.DataSource = Range(414000, 10, 460000); - RMIN_FREQ.DataSource = Range(414000, 10, 460000); + MIN_FREQ.DataSource = Range(414000, 50, 460000); + RMIN_FREQ.DataSource = Range(414000, 50, 460000); - MAX_FREQ.DataSource = Range(414000, 10, 460000); - RMAX_FREQ.DataSource = Range(414000, 10, 460000); + MAX_FREQ.DataSource = Range(414000, 50, 460000); + RMAX_FREQ.DataSource = Range(414000, 50, 460000); } else if (freq == Uploader.Frequency.FREQ_868) { @@ -1053,35 +1661,44 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) if (multipoint_fix == -1) { - var AESKey = doCommand(Session.Port, "AT&E?").Trim(); + var AESKey = doCommand(Session.Port, "AT&E?").Trim(); //Session.ATCClient.DoQuery("AT&E?", true);// doCommand(Session.Port, "AT&E?").Trim(); if (AESKey.Contains("ERROR")) { - txt_aeskey.Text = ""; - txt_aeskey.Enabled = false; + AESKEY.Text = ""; + AESKEY.Enabled = false; } else { - txt_aeskey.Text = AESKey; - txt_aeskey.Enabled = true; + AESKEY.Text = AESKey; + AESKEY.Enabled = true; } SetupComboForMavlink(MAVLINK, false); } else { - txt_aeskey.Text = ""; - txt_aeskey.Enabled = false; + AESKEY.Text = ""; + AESKEY.Enabled = false; SetupComboForMavlink(MAVLINK, true); } - RSSI.Text = doCommand(Session.Port, "ATI7").Trim(); + RSSI.Text = doCommand(Session.Port, "ATI7").Trim(); //Session.ATCClient.DoQuery("ATI7", true);// doCommand(Session.Port, "ATI7").Trim(); + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done ATI7 cmd"); + lbl_status.Text = "Doing Command ATI5"; - var answer = doCommand(Session.Port, "ATI5", true); + var answer = doCommand(Session.Port, "ATI5", true); //Session.ATCClient.DoQueryWithMultiLineResponse("ATI5");// doCommand(Session.Port, "ATI5", true); + + bool Junk; + + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Parsing local settings"); - var Settings = Session.GetSettings( - doCommand(Session.Port, "ATI5?", true), - Session.Board); + var Settings = Session.GetSettings(false, + Session.Board, answer, null, out Junk); + + _LocalSettings = new RFD.RFD900.TSettings( + RFDLib.Collections.Translate( + Settings, (x) => (RFD.RFD900.TBaseSetting)x)); DisableRFD900xControls(); @@ -1092,90 +1709,45 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) kvp.Key.Enabled = kvp.Value; } + btnSaveToFile.Enabled = true; + btnLoadFromFile.Enabled = true; + + _LocalLabelEditorPairs.Reset(); + if (ATI.Text.Contains("ASYNC")) { - _LocalExtraParams.SetModel(Model.ASYNC); + _LocalExtraParams.SetModel(Model.ASYNC, Settings); } else { - if ((items.Length > 0) && items[0].StartsWith("[")) + if (ATI.Text.Contains("MP on") && (Session.Board == Uploader.Board.DEVICE_ID_RFD900X)) { //This is multipoint firmware. - _LocalExtraParams.SetModel(Model.MULTIPOINT); + _LocalExtraParams.SetModel(Model.MULTIPOINT_X, Settings); } - else if (ATI.Text.Contains("MP on") && (Session.Board == Uploader.Board.DEVICE_ID_RFD900X)) + else if ((items.Length > 0) && items[0].StartsWith("[")) { - _LocalExtraParams.SetModel(Model.MULTIPOINT_X); + _LocalExtraParams.SetModel(Model.MULTIPOINT, Settings); } else { //This is p2p firmware. - _LocalExtraParams.SetModel(Model.P2P); + _LocalExtraParams.SetModel(Model.P2P, Settings); } } + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done getting info out of local modem"); + //For each of the settings returned by the radio... - foreach (var item in items) - { - //if (item.StartsWith("S")) - { - var mod_item = item; - if (multipoint_fix > 0 && item.Length > multipoint_fix) - { - mod_item = item.Substring(multipoint_fix).Trim(); - } - var values = mod_item.Split(new char[] { ':', '=' }, StringSplitOptions.RemoveEmptyEntries); + SetUpControlsWithValues(groupBoxLocal, false, ModifyReturnedStringsForMultipoint(items, multipoint_fix), Settings); - if (values.Length == 3) - { - values[1] = values[1].Replace("/", "_"); - - var controls = groupBoxLocal.Controls.Find(values[1].Trim(), true); - - //If there's a control with the same name as the setting... - if (controls.Length > 0) - { - groupBoxLocal.Enabled = true; - controls[0].Parent.Enabled = true; - controls[0].Enabled = true; - - if (controls[0] is CheckBox) - { - ((CheckBox)controls[0]).Checked = values[2].Trim() == "1"; - } - else if (controls[0] is TextBox) - { - ((TextBox)controls[0]).Text = values[2].Trim(); - } - else if (controls[0].Name.Contains("MAVLINK")) // - { - var ans = Enum.Parse(typeof(mavlink_option), values[2].Trim()); - ((ComboBox)controls[0]).Text = ans.ToString(); - } - else if (controls[0] is ComboBox) - { - if (!SetupCBWithSetting((ComboBox)controls[0], Settings, - values[2].Trim(), false)) - { - ((ComboBox)controls[0]).Text = values[2].Trim(); - if (((ComboBox)controls[0]).Text != values[2].Trim()) - { - SomeSettingsInvalid = true; - - } - - } - - } - } - } - } - } + btnRandom.Enabled = GetIsEncryptionEnabled(ENCRYPTION_LEVEL); + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done setting up controls for local modem"); // remote foreach (Control ctl in groupBoxRemote.Controls) { - if ((ctl.Name != "RSSI")&& (!(ctl is Label))) + if ((ctl.Name != "RSSI")&& (!(ctl is Label)) && !(ctl is Button)) { ctl.ResetText(); } @@ -1183,7 +1755,20 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) Session.Port.DiscardInBuffer(); - RTI.Text = doCommand(Session.Port, "RTI"); + string RTIText = doCommand(Session.Port, "RTI"); + + if ((RTIText.Length < 5) || RTIText.Substring(0, 5) == "ERROR") + { + RTI.Text = ""; + } + else + { + RTI.Text = RTIText; + } + + string RemoteFWVer = RFD.RFD900.RFD900.ATIResponseToFWVersion(RTI.Text); + + txtRCountry.Text = GetCountryCodeFromSession(Session, (m) => m.GetRemoteCountryCode()); if (RTI.Text != "") { @@ -1204,20 +1789,20 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) var AESKey = doCommand(Session.Port, "RT&E?").Trim(); if (AESKey.Contains("ERROR")) { - txt_Raeskey.Text = ""; - txt_Raeskey.Enabled = false; + RAESKEY.Text = ""; + RAESKEY.Enabled = false; } else { - txt_Raeskey.Text = AESKey; - txt_Raeskey.Enabled = true; + RAESKEY.Text = AESKey; + RAESKEY.Enabled = true; } SetupComboForMavlink(RMAVLINK, false); } else { - txt_Raeskey.Text = ""; - txt_Raeskey.Enabled = false; + RAESKEY.Text = ""; + RAESKEY.Enabled = false; SetupComboForMavlink(RMAVLINK, true); } @@ -1225,92 +1810,53 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) answer = doCommand(Session.Port, "RTI5", true); + bool UsedAltRanges; + + var RemoteSettings = Session.GetSettings(true, Session.Board, answer, (LocalFWVer == RemoteFWVer) ? Settings : null, out UsedAltRanges); + + _RemoteSettings = new RFD.RFD900.TSettings( + RFDLib.Collections.Translate( + RemoteSettings, (x) => (RFD.RFD900.TBaseSetting)x)); + + if ((RemoteFWVer != null) && (LocalFWVer != RemoteFWVer) && UsedAltRanges) + { + MsgBox.CustomMessageBox.Show("The ranges and options shown for the remote modem may not be accurate. To ensure accurate, use the same firmware version in both the local and remote modems"); + } + items = answer.Split('\n'); + _RemoteLabelEditorPairs.Reset(); + + btnRemoteSaveToFile.Enabled = true; + btnRemoteLoadFromFile.Enabled = true; if (RTI.Text.Contains("ASYNC")) { - _RemoteExtraParams.SetModel(Model.ASYNC); + _RemoteExtraParams.SetModel(Model.ASYNC, RemoteSettings); } else { - if ((items.Length > 0) && items[0].StartsWith("[")) + if (RTI.Text.Contains("MP on") && (Session.Board == Uploader.Board.DEVICE_ID_RFD900X)) { - //This is multipoint firmware. - _RemoteExtraParams.SetModel(Model.MULTIPOINT); + _RemoteExtraParams.SetModel(Model.MULTIPOINT_X, RemoteSettings); } - else if (RTI.Text.Contains("MP on") && (Session.Board == Uploader.Board.DEVICE_ID_RFD900X)) + else if ((items.Length > 0) && items[0].StartsWith("[")) { - _RemoteExtraParams.SetModel(Model.MULTIPOINT_X); + //This is multipoint firmware. + _RemoteExtraParams.SetModel(Model.MULTIPOINT, RemoteSettings); } else { //This is 2-point firmware. - _RemoteExtraParams.SetModel(Model.P2P); + _RemoteExtraParams.SetModel(Model.P2P, RemoteSettings); } } - foreach (var item in items) - { - //if (item.StartsWith("S")) - { - var values = item.Split(new char[] { ':', '=' }, StringSplitOptions.RemoveEmptyEntries); - - if (values.Length == 3) - { - values[1] = values[1].Replace("/", "_"); - - var controls = groupBoxRemote.Controls.Find("R" + values[1].Trim(), true); - - if (controls.Length == 0) - continue; - - - controls[0].Enabled = true; - - if (controls[0] is CheckBox) - { - ((CheckBox)controls[0]).Checked = values[2].Trim() == "1"; - } - else if (controls[0] is TextBox) - { - ((TextBox)controls[0]).Text = values[2].Trim(); - } - else if (controls[0].Name.Contains("MAVLINK")) // - { - var ans = Enum.Parse(typeof(mavlink_option), values[2].Trim()); - ((ComboBox)controls[0]).Text = ans.ToString(); - } - else if (controls[0] is ComboBox) - { - if (!SetupCBWithSetting((ComboBox)controls[0], Settings, - values[2].Trim(), true)) - { - ((ComboBox)controls[0]).Text = values[2].Trim(); - if (((ComboBox)controls[0]).Text != values[2].Trim()) - { - SomeSettingsInvalid = true; - } - } - } - } - else - { - /* - if (item.Contains("S15")) - { - answer = doCommand(comPort, "RTS15?"); - int rts15 = 0; - if (int.TryParse(answer, out rts15)) - { - RS15.Enabled = true; - RS15.Text = rts15.ToString(); - } - } - */ - log.Info("Odd config line :" + item); - } - } - } + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done getting info from remote modem"); + + SomeSettingsInvalid |= SetUpControlsWithValues(groupBoxRemote, true, items, RemoteSettings); + + //System.Diagnostics.Debug.WriteLine(SW.ElapsedMilliseconds.ToString() + ": Done setting up controls for remote modem"); + } // off hook @@ -1324,6 +1870,9 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) { lbl_status.Text = "Done"; } + EnableConfigControls(true, true); + + } else { @@ -1331,7 +1880,8 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) Session.PutIntoTransparentMode(); lbl_status.Text = "Fail"; - MsgBox.CustomMessageBox.Show("Failed to enter command mode"); + MsgBox.CustomMessageBox.Show("Failed to enter command mode. Try power-cycling modem."); + EnableConfigControls(true, false); } //BUT_Syncoptions.Enabled = true; @@ -1339,8 +1889,6 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) //BUT_savesettings.Enabled = true; //BUT_SetPPMFailSafe.Enabled = true; - - EnableConfigControls(true); EnableProgrammingControls(true); } @@ -1349,11 +1897,15 @@ private void BUT_getcurrent_Click(object sender, EventArgs e) lbl_status.Text = "Error"; MsgBox.CustomMessageBox.Show("Error during read " + ex); } + _AlreadyInEncCheckChangedEvtHdlr = false; - if (GetCommsSerialAlt == null) - { - EndSessionClosePort(); - } + UpdateSetPPMFailSafeButtons(); + } + + void UpdateSetPPMFailSafeButtons() + { + BUT_SetPPMFailSafe.Enabled = GPO1_1R_COUT.Enabled && GPO1_1R_COUT.Checked; + BUT_SetPPMFailSafeRemote.Enabled = RGPO1_1R_COUT.Enabled && RGPO1_1R_COUT.Checked; } private string Serial_ReadLine(ICommsSerial comPort) @@ -1365,8 +1917,8 @@ private string Serial_ReadLine(ICommsSerial comPort) { if (comPort.BytesToRead > 0) { - var data = (byte)comPort.ReadByte(); - sb.Append((char)data); + var data = (byte) comPort.ReadByte(); + sb.Append((char) data); if (data == '\n') break; } @@ -1463,7 +2015,7 @@ public bool doConnect(ICommsSerial comPort) // setup a known enviroment comPort.Write("ATO\r\n"); - retry: + retry: // wait Sleep(1500, comPort); @@ -1531,8 +2083,8 @@ private void BUT_Syncoptions_Click(object sender, EventArgs e) RMAX_FREQ.Text = MAX_FREQ.Text; RNUM_CHANNELS.Text = NUM_CHANNELS.Text; RMAX_WINDOW.Text = MAX_WINDOW.Text; - RENCRYPTION_LEVEL.Checked = ENCRYPTION_LEVEL.Checked; - txt_Raeskey.Text = txt_aeskey.Text; + RENCRYPTION_LEVEL.SelectedIndex = ENCRYPTION_LEVEL.SelectedIndex; + RAESKEY.Text = AESKEY.Text; } private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e) @@ -1608,11 +2160,7 @@ private void BUT_resettodefault_Click(object sender, EventArgs e) Session.PutIntoTransparentMode(); lbl_status.Text = "Fail"; - MsgBox.CustomMessageBox.Show("Failed to enter command mode"); - } - if (GetCommsSerialAlt == null) - { - EndSessionClosePort(); + MsgBox.CustomMessageBox.Show("Failed to enter command mode. Try power-cycling modem."); } } @@ -1623,14 +2171,26 @@ void UpdateStatus(string Status) Application.DoEvents(); } - void EnableConfigControls(bool Enable) + void UpdateStatusCallback(string Status, double Progress) + { + if (Status != null) + { + UpdateStatus(Status); + } + if (!double.IsNaN(Progress)) + { + ProgressEvtHdlr(Progress); + } + } + + void EnableConfigControls(bool Enable, bool SaveSettingsEnable) { - groupBoxLocal.Enabled = Enable; - groupBoxRemote.Enabled = Enable; + groupBoxLocal.Enabled = SaveSettingsEnable; + groupBoxRemote.Enabled = SaveSettingsEnable; BUT_Syncoptions.Enabled = Enable; BUT_SetPPMFailSafe.Enabled = Enable; BUT_getcurrent.Enabled = Enable; - BUT_savesettings.Enabled = Enable; + BUT_savesettings.Enabled = SaveSettingsEnable; BUT_resettodefault.Enabled = Enable; } public static void ResetAllControls(Control form) @@ -1688,7 +2248,7 @@ private void BUT_loadcustom_Click(object sender, EventArgs e) void ProgramFirmware(bool Custom) { EnableProgrammingControls(false); - EnableConfigControls(false); + EnableConfigControls(false, false); try { @@ -1700,23 +2260,13 @@ void ProgramFirmware(bool Custom) //Console.WriteLine("Mode is " + Mode.ToString()); //port.Close(); - RFD.RFD900.RFD900 RFD900 = null; - UpdateStatus("Putting in to bootloader mode"); - switch (Session.PutIntoBootloaderMode()) - { - case RFD.RFD900.TSession.TMode.BOOTLOADER: - RFD900 = RFD.RFD900.RFD900APU.GetObjectForModem(Session); - break; - case RFD.RFD900.TSession.TMode.BOOTLOADER_X: - RFD900 = RFD.RFD900.RFD900xux.GetObjectForModem(Session); - break; - default: - break; - } + RFD.RFD900.RFD900 RFD900 = _Session.GetModemObject(); if (RFD900 == null) { - UpdateStatus("Could not put in to bootloader mode"); + UpdateStatus("Unknown modem"); + MsgBox.CustomMessageBox.Show("Couldn't communicate with modem. Try power-cycling modem."); + EndSession(); } else { @@ -1728,10 +2278,10 @@ void ProgramFirmware(bool Custom) { UpdateStatus("Getting firmware from internet"); } - if (getFirmware(RFD900.Board, Custom)) + if (getFirmware(RFD900.Board, RFD900, Custom)) { UpdateStatus("Programming firmware into device"); - if (RFD900.ProgramFirmware(firmwarefile, ProgressEvtHdlr)) + if (RFD900.ProgramFirmware(firmwarefile, UpdateStatusCallback)) { UpdateStatus("Programmed firmware into device"); } @@ -1739,6 +2289,7 @@ void ProgramFirmware(bool Custom) { UpdateStatus("Programming failed. (Try again?)"); } + EndSession(); } else { @@ -1748,15 +2299,18 @@ void ProgramFirmware(bool Custom) } catch { - + try + { + UpdateStatus("Programming failed. (Try again?)"); + EndSession(); + } + catch + { + } } EnableProgrammingControls(true); - EnableConfigControls(true); + EnableConfigControls(true, false); //UploadFW(true); - if (GetCommsSerialAlt == null) - { - EndSessionClosePort(); - } } void ProgressEvtHdlr(double Completed) @@ -1799,7 +2353,7 @@ private void linkLabel_lowlatency_LinkClicked(object sender, LinkLabelLinkClicke RMAX_WINDOW.Text = 33.ToString(); } - private enum mavlink_option + public enum mavlink_option { RawData = 0, Mavlink = 1, @@ -1819,15 +2373,14 @@ private void txt_aeskey_TextChanged(object sender, EventArgs e) string item = txt.Text; if (!(Regex.IsMatch(item, "^[0-9a-fA-F]+$"))) { - if (item.Length != 0) + if(item.Length != 0) txt.Text = item.Remove(item.Length - 1, 1); txt.SelectionStart = txt.Text.Length; } } - private void BUT_SetPPMFailSafe_Click(object sender, EventArgs e) + private void SetPPMFailSafe(string SetCmd, string SaveCmd) { - lbl_status.Text = "Connecting"; RFD.RFD900.TSession Session = GetSession(); @@ -1839,18 +2392,21 @@ private void BUT_SetPPMFailSafe_Click(object sender, EventArgs e) if (Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND) { // cleanup - doCommand(Session.Port, "AT&T", false, 1); - - Session.Port.DiscardInBuffer(); + //Session.Port.DiscardInBuffer(); + //doCommand(Session.Port, "AT&T", false, 1); lbl_status.Text = "Doing Command"; - string Result = doCommand(Session.Port, "RT&R"); + Session.Port.DiscardInBuffer(); + bool Result = Session.ATCClient.DoCommand(SetCmd); + + Session.Port.DiscardInBuffer(); + Session.ATCClient.DoCommand(SaveCmd); // off hook //doCommand(Session.Port, "ATO"); - if (Result.Contains("OK")) + if (Result) { lbl_status.Text = "Done"; } @@ -1867,85 +2423,26 @@ private void BUT_SetPPMFailSafe_Click(object sender, EventArgs e) lbl_status.Text = "Fail"; MsgBox.CustomMessageBox.Show("Failed to enter command mode"); } - - if (GetCommsSerialAlt == null) - { - EndSessionClosePort(); - } } - void getTelemPortWithRadio(ref ICommsSerial comPort) - { - // try telem1 - - comPort = new MAVLinkSerialPort(MainV2.comPort, (int)MAVLink.SERIAL_CONTROL_DEV.TELEM1); - - comPort.ReadTimeout = 4000; - - comPort.Open(); - } - /// - /// returns null if failed - /// - /// - ICommsSerial GetComPort() + private void BUT_SetPPMFailSafe_Click(object sender, EventArgs e) { - if (GetCommsSerialAlt == null) - { - ICommsSerial comPort; - - try - { - if (MainV2.comPort.BaseStream.PortName.Contains("TCP")) - { - comPort = new TcpSerial(); - comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate; - comPort.ReadTimeout = 4000; - comPort.Open(); - } - else - { - comPort = new SerialPort(); - if (MainV2.comPort.BaseStream.IsOpen) - { - getTelemPortWithRadio(ref comPort); - } - else - { - comPort.PortName = MainV2.comPortName; - comPort.BaudRate = MainV2.comPortBaud; - } - - comPort.ReadTimeout = 4000; - - comPort.Open(); - } - - return comPort; - } - catch - { - MsgBox.CustomMessageBox.Show("Invalid ComPort or in use"); - return null; - } - } - else - { - return GetCommsSerialAlt(); - } + SetPPMFailSafe("AT&R", "AT&W"); } RFD.RFD900.TSession GetSession() { + if (_Session == null) { try { - var p = GetComPort(); + var p = MissionPlanner.Radio.ComPort.GetComPortForSiKRadio(); + if (p != null) { - _Session = new RFD.RFD900.TSession(p); + _Session = new RFD.RFD900.TSession(p, MainV2.comPort.BaseStream.BaudRate); } } catch @@ -1964,29 +2461,16 @@ RFD.RFD900.TSession GetSession() return _Session; } - /// - /// Put the modem into transparent mode and close the comms port. - /// - private void EndSessionClosePort() + private void EndSession() { if (_Session != null) { - try - { - _Session.PutIntoTransparentMode(); - } catch{} _Session.Dispose(); - _Session.Port.Close(); _Session = null; } - } - - private void EndSession() - { - if (_Session != null) + if (DoDisconnectReconnect != null) { - _Session.Dispose(); - _Session = null; + DoDisconnectReconnect(); } } @@ -2012,8 +2496,11 @@ bool SetSetting(string Designator, int Value, bool Remote) /// ignored private void ENCRYPTION_LEVEL_CheckedChanged(object sender, EventArgs e) { - EncryptionCheckChangedEvtHdlr(ENCRYPTION_LEVEL, "ATI5", "AT&E?", txt_aeskey, false); - btnRandom.Enabled = ENCRYPTION_LEVEL.Checked; + if (ENCRYPTION_LEVEL.Enabled) + { + EncryptionCheckChangedEvtHdlr(ENCRYPTION_LEVEL, "ATI5", "AT&E?", AESKEY, false, "ATI5"); + } + btnRandom.Enabled = GetIsEncryptionEnabled(ENCRYPTION_LEVEL); } /// @@ -2023,19 +2510,38 @@ private void ENCRYPTION_LEVEL_CheckedChanged(object sender, EventArgs e) /// ignored private void RENCRYPTION_LEVEL_CheckedChanged(object sender, EventArgs e) { - EncryptionCheckChangedEvtHdlr(RENCRYPTION_LEVEL, "RTI5", "RT&E?", txt_Raeskey, true); + if (RENCRYPTION_LEVEL.Enabled) + { + EncryptionCheckChangedEvtHdlr(RENCRYPTION_LEVEL, "RTI5", "RT&E?", RAESKEY, true, "RTI5"); + } } bool _AlreadyInEncCheckChangedEvtHdlr = false; + string RemoveMultiPointLocalNodeID(string ATCReply) + { + ATCReply = ATCReply.Trim(); + + if ((ATCReply.Length > 1) && (ATCReply[0] == '[') && ATCReply.Contains(']')) + { + int StartIndex = ATCReply.IndexOf(']') + 1; + + return ATCReply.Substring(StartIndex); + } + else + { + return ATCReply; + } + } + /// /// Handles a change of an encryption level check box. /// /// The checkbox which was changed. Must not be null. /// The AT command to use to get the settings /// from the relevant modem. Must not be null. - void EncryptionCheckChangedEvtHdlr(CheckBox CB, string ATCommand, string EncKeyQuery, - TextBox EncKeyTextBox, bool Remote) + void EncryptionCheckChangedEvtHdlr(ComboBox CB, string ATCommand, string EncKeyQuery, + TextBox EncKeyTextBox, bool Remote, string ATI5Command) { if (_AlreadyInEncCheckChangedEvtHdlr) { @@ -2052,12 +2558,15 @@ void EncryptionCheckChangedEvtHdlr(CheckBox CB, string ATCommand, string EncKeyQ return; } Session.PutIntoATCommandMode(); - var answer = doCommand(Session.Port, ATCommand, true); - var Settings = Session.GetSettings(answer, Session.Board); + var ATI5answer = doCommand(Session.Port, ATI5Command, true); + + bool Junk; + + var Settings = Session.GetSettings(Remote, Session.Board, ATI5answer, null, out Junk); if (Settings.ContainsKey("ENCRYPTION_LEVEL")) { var Setting = Settings["ENCRYPTION_LEVEL"]; - if (!SetSetting(Setting.Designator, CB.Checked ? 1 : 0, Remote)) + if (!SetSetting(Setting.Designator, GetEncryptionLevelValue(CB), Remote)) { return; } @@ -2070,11 +2579,7 @@ void EncryptionCheckChangedEvtHdlr(CheckBox CB, string ATCommand, string EncKeyQ //Read AES key back out of modem and display it. //BUT_getcurrent_Click(this, null); //txt_aeskey.Text = doCommand(Session.Port, "AT&E?").Trim(); - EncKeyTextBox.Text = doCommand(Session.Port, EncKeyQuery).Trim(); - if (CB.Checked && EncKeyTextBox.Text.Length == 0) - { - //Console.WriteLine("Something wrong here"); - } + EncKeyTextBox.Text = RemoveMultiPointLocalNodeID(doCommand(Session.Port, EncKeyQuery).Trim()).Trim(); lbl_status.Text = "Done."; } finally @@ -2083,27 +2588,144 @@ void EncryptionCheckChangedEvtHdlr(CheckBox CB, string ATCommand, string EncKeyQ } } - string GetRandom32BitKey() + /// + /// Get a random key as a hex numeral string, with the given QTY of hex numerals. + /// + /// The QTY of hex numerals. + /// The key. Never null. + string GetRandomKey(int QTYHexDigits) { + string Result = ""; + System.Random R = new Random((int)(System.DateTime.Now.Ticks & 0xFFFFFFFF)); - return R.Next().ToString("X8"); - } - string GetRandomKey() - { - return GetRandom32BitKey() + GetRandom32BitKey() + GetRandom32BitKey() + GetRandom32BitKey(); + for (; QTYHexDigits > 0; QTYHexDigits--) + { + Result += (((UInt32)R.Next()) & 0xF).ToString("X1"); + } + + return Result; } private void btnRandom_Click(object sender, EventArgs e) { - //Key is 16 binary bytes (32 hex digits) - txt_aeskey.Text = GetRandomKey(); - txt_Raeskey.Text = txt_aeskey.Text; + AESKEY.Text = GetRandomKey(GetEncryptionMaxKeyLength(ENCRYPTION_LEVEL)); + RAESKEY.Text = AESKEY.Text; } private void btnCommsLog_Click(object sender, EventArgs e) { } + + private void BUT_SetPPMFailSafeRemote_Click(object sender, EventArgs e) + { + SetPPMFailSafe("RT&R", "RT&W"); + } + + /// + /// Save settings from GUI to file. + /// + /// The settings read from the modem. Must not be null. + /// The relevant GUI groupbox. + /// true if remote modem, false if local modem. + void SaveToFile(RFD.RFD900.TSettings S, GroupBox GB, + bool Remote) + { + //Get the settings which have changed in the GUI, and their values. + var Updated = GetUpdatedSettingsFromGroupBox( + RFDLib.Collections.Translate(S.Settings, (x) => (RFD.RFD900.TBaseSetting)x), + GB, Remote); + + //Include the settings which haven't changed. + foreach (var kvp in S.Settings) + { + if (!Updated.ContainsKey(kvp.Key)) + { + Updated[kvp.Key] = kvp.Value; + } + } + + //Save to file... + RFD.RFD900.TSettings ToSave = new RFD.RFD900.TSettings(Updated); + + if (dlgSave.ShowDialog() == DialogResult.OK) + { + if (ToSave.SaveToFile(dlgSave.FileName)) + { + System.Windows.Forms.MessageBox.Show("Saved settings to " + dlgSave.FileName + " OK"); + } + else + { + System.Windows.Forms.MessageBox.Show("Failed to save settings to " + dlgSave.FileName); + } + } + } + + private void btnSaveToFile_Click(object sender, EventArgs e) + { + SaveToFile(_LocalSettings, groupBoxLocal, false); + } + + /// + /// Load settings from file into the GUI. + /// + /// The settings loaded from the modem. These aren't modified by this function. Must not be null. + /// The relevant GUI groupbox. Must not be null. + /// true if for the remote modem, false if for the local modem. + private void LoadFromFile(RFD.RFD900.TSettings S, GroupBox GB, bool Remote) + { + if (dlgOpen.ShowDialog() == DialogResult.OK) + { + S = S.Clone(); + + var x = S.LoadFromFile(dlgOpen.FileName); + + if (x == null) + { + System.Windows.Forms.MessageBox.Show("Failed to load settings from " + dlgOpen.FileName); + } + else + { + UpdateControlsWithValues(GB, Remote, S.Settings); + + string Temp = "Loaded\n"; + + foreach (var kvp in x) + { + Temp += kvp.Value.Name + " = " + kvp.Value.Value.ToString() + "\n"; + } + + Temp += "from " + dlgOpen.FileName + " OK"; + + System.Windows.Forms.MessageBox.Show(Temp); + } + } + } + + + private void btnLoadFromFile_Click(object sender, EventArgs e) + { + LoadFromFile(_LocalSettings, groupBoxLocal, false); + } + + private void btnRemoteLoadFromFile_Click(object sender, EventArgs e) + { + LoadFromFile(_RemoteSettings, groupBoxRemote, true); + } + + private void btnRemoteSaveToFile_Click(object sender, EventArgs e) + { + SaveToFile(_RemoteSettings, groupBoxRemote, true); + } + + public string Header + { + get + { + return "Settings"; + } + } + } } \ No newline at end of file diff --git a/Radio/Sikradio.resx b/Radio/Sikradio.resx index bc9078141d..aad3baa0cf 100644 --- a/Radio/Sikradio.resx +++ b/Radio/Sikradio.resx @@ -123,7 +123,7 @@ - 12, 447 + 12, 561 1072, 36 @@ -179,7 +179,7 @@ which result in a valid packet CRC groupBoxLocal - 63 + 86 True @@ -216,7 +216,7 @@ red LED solid - in firmware update mode $this - 4 + 3 False @@ -225,7 +225,7 @@ red LED solid - in firmware update mode NoControl - 266, 217 + 266, 207 80, 20 @@ -246,7 +246,7 @@ red LED solid - in firmware update mode groupBoxRemote - 42 + 65 False @@ -345,7 +345,7 @@ red LED solid - in firmware update mode 30 - 266, 244 + 266, 232 80, 21 @@ -353,9 +353,6 @@ red LED solid - in firmware update mode 96 - - Node ID. Base node ID is 0. One node must be acting as a base for a multipoint environment to work. - RMAX_WINDOW @@ -366,7 +363,7 @@ red LED solid - in firmware update mode groupBoxRemote - 45 + 68 False @@ -399,7 +396,7 @@ red LED solid - in firmware update mode 435000 - 266, 108 + 266, 107 80, 21 @@ -420,7 +417,7 @@ red LED solid - in firmware update mode groupBoxRemote - 47 + 70 False @@ -483,7 +480,7 @@ red LED solid - in firmware update mode 50 - 266, 135 + 266, 132 80, 21 @@ -504,7 +501,7 @@ red LED solid - in firmware update mode groupBoxRemote - 48 + 71 False @@ -540,7 +537,7 @@ red LED solid - in firmware update mode 100 - 266, 162 + 266, 157 80, 21 @@ -561,7 +558,7 @@ red LED solid - in firmware update mode groupBoxRemote - 49 + 72 False @@ -588,7 +585,7 @@ red LED solid - in firmware update mode 250 - 266, 189 + 266, 182 80, 21 @@ -609,7 +606,7 @@ red LED solid - in firmware update mode groupBoxRemote - 50 + 73 False @@ -642,7 +639,7 @@ red LED solid - in firmware update mode 435000 - 266, 83 + 266, 82 80, 21 @@ -663,13 +660,13 @@ red LED solid - in firmware update mode groupBoxRemote - 51 + 74 False - 88, 243 + 88, 232 80, 21 @@ -677,9 +674,6 @@ red LED solid - in firmware update mode 111 - - AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. - RMAVLINK @@ -690,7 +684,7 @@ red LED solid - in firmware update mode groupBoxRemote - 9 + 33 False @@ -699,17 +693,16 @@ red LED solid - in firmware update mode NoControl - 102, 323 + 148, 307 - 66, 20 + 20, 20 119 - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - + GPI1_1R/COUT Sets GPIO 1.1 as R/C(PPM) output RGPO1_1R_COUT @@ -721,7 +714,7 @@ red LED solid - in firmware update mode groupBoxRemote - 10 + 34 False @@ -730,17 +723,16 @@ red LED solid - in firmware update mode NoControl - 88, 297 + 148, 282 - 80, 20 + 20, 20 115 - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - + GPI1_1R/CIN Sets GPIO 1.1 as R/C(PPM) input RGPI1_1R_CIN @@ -752,7 +744,7 @@ red LED solid - in firmware update mode groupBoxRemote - 13 + 37 False @@ -785,7 +777,7 @@ red LED solid - in firmware update mode 1 - 88, 109 + 88, 107 80, 21 @@ -807,7 +799,7 @@ red LED solid - in firmware update mode groupBoxRemote - 14 + 38 False @@ -852,7 +844,7 @@ red LED solid - in firmware update mode 2 - 88, 136 + 88, 132 80, 21 @@ -873,7 +865,7 @@ red LED solid - in firmware update mode groupBoxRemote - 15 + 39 False @@ -969,7 +961,7 @@ red LED solid - in firmware update mode 30 - 88, 163 + 88, 157 80, 21 @@ -990,7 +982,7 @@ red LED solid - in firmware update mode groupBoxRemote - 16 + 40 False @@ -1020,7 +1012,7 @@ red LED solid - in firmware update mode 20 - 88, 191 + 88, 182 80, 21 @@ -1042,7 +1034,7 @@ red LED solid - in firmware update mode groupBoxRemote - 18 + 42 False @@ -1051,7 +1043,7 @@ red LED solid - in firmware update mode NoControl - 88, 217 + 88, 207 80, 20 @@ -1073,7 +1065,7 @@ red LED solid - in firmware update mode groupBoxRemote - 20 + 44 False @@ -1082,10 +1074,10 @@ red LED solid - in firmware update mode NoControl - 88, 271 + 148, 257 - 80, 20 + 20, 20 120 @@ -1104,7 +1096,7 @@ red LED solid - in firmware update mode groupBoxRemote - 23 + 47 False @@ -1113,7 +1105,7 @@ red LED solid - in firmware update mode NoControl - 274, 216 + 274, 207 80, 20 @@ -1134,7 +1126,7 @@ red LED solid - in firmware update mode groupBoxLocal - 43 + 66 False @@ -1233,7 +1225,7 @@ red LED solid - in firmware update mode 30 - 274, 243 + 274, 232 80, 21 @@ -1241,9 +1233,6 @@ red LED solid - in firmware update mode 92 - - Node ID. Base node ID is 0. One node must be acting as a base for a multipoint environment to work. - MAX_WINDOW @@ -1254,7 +1243,7 @@ red LED solid - in firmware update mode groupBoxLocal - 48 + 71 False @@ -1308,7 +1297,7 @@ red LED solid - in firmware update mode groupBoxLocal - 50 + 73 False @@ -1371,7 +1360,7 @@ red LED solid - in firmware update mode 50 - 274, 134 + 274, 132 80, 21 @@ -1392,7 +1381,7 @@ red LED solid - in firmware update mode groupBoxLocal - 51 + 74 False @@ -1419,7 +1408,7 @@ red LED solid - in firmware update mode 250 - 274, 188 + 274, 182 80, 21 @@ -1440,7 +1429,7 @@ red LED solid - in firmware update mode groupBoxLocal - 53 + 76 False @@ -1503,7 +1492,7 @@ red LED solid - in firmware update mode groupBoxLocal - 55 + 78 False @@ -1539,7 +1528,7 @@ red LED solid - in firmware update mode 100 - 274, 161 + 274, 157 80, 21 @@ -1560,7 +1549,7 @@ red LED solid - in firmware update mode groupBoxLocal - 58 + 81 False @@ -1569,17 +1558,16 @@ red LED solid - in firmware update mode NoControl - 110, 323 + 154, 307 - 66, 20 + 23, 20 129 - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - + GPI1_1R/COUT Sets GPIO 1.1 as R/C(PPM) output GPO1_1R_COUT @@ -1591,7 +1579,7 @@ red LED solid - in firmware update mode groupBoxLocal - 10 + 34 False @@ -1600,17 +1588,16 @@ red LED solid - in firmware update mode NoControl - 96, 297 + 154, 282 - 80, 20 + 23, 20 127 - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. - + GPI1_1R/CIN Sets GPIO 1.1 as R/C(PPM) input GPI1_1R_CIN @@ -1622,13 +1609,13 @@ red LED solid - in firmware update mode groupBoxLocal - 12 + 36 False - 96, 244 + 96, 232 80, 21 @@ -1637,7 +1624,7 @@ red LED solid - in firmware update mode 126 - AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max is 192, min is 2. I would not recommend values below 16 as the frequency hopping and tdm sync times get too long. + Mavlink MAVLINK @@ -1649,7 +1636,7 @@ red LED solid - in firmware update mode groupBoxLocal - 13 + 37 False @@ -1682,7 +1669,7 @@ red LED solid - in firmware update mode 1 - 96, 109 + 96, 107 80, 21 @@ -1704,7 +1691,7 @@ red LED solid - in firmware update mode groupBoxLocal - 15 + 39 False @@ -1749,7 +1736,7 @@ red LED solid - in firmware update mode 2 - 96, 136 + 96, 132 80, 21 @@ -1770,7 +1757,7 @@ red LED solid - in firmware update mode groupBoxLocal - 18 + 42 False @@ -1866,7 +1853,7 @@ red LED solid - in firmware update mode 30 - 96, 163 + 96, 157 80, 21 @@ -1887,7 +1874,7 @@ red LED solid - in firmware update mode groupBoxLocal - 20 + 44 False @@ -1917,7 +1904,7 @@ red LED solid - in firmware update mode 20 - 96, 191 + 96, 182 80, 21 @@ -1939,7 +1926,7 @@ red LED solid - in firmware update mode groupBoxLocal - 22 + 46 False @@ -1948,7 +1935,7 @@ red LED solid - in firmware update mode NoControl - 96, 217 + 96, 207 80, 20 @@ -1970,7 +1957,7 @@ red LED solid - in firmware update mode groupBoxLocal - 24 + 48 False @@ -1979,10 +1966,10 @@ red LED solid - in firmware update mode NoControl - 96, 271 + 154, 257 - 80, 20 + 23, 20 124 @@ -2001,710 +1988,1832 @@ red LED solid - in firmware update mode groupBoxLocal - 27 + 51 - - 60, 12 + + False - - 147, 20 + + 0 - - 33 + + 1 - - RTI + + 2 - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 3 - - groupBoxRemote + + 4 - - 58 + + 5 - - 59, 12 + + 6 - - 147, 20 + + 7 - - 32 + + 8 - - ATI + + 9 - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 10 - - groupBoxLocal + + 11 - - 62 + + 12 - - True + + 13 - - NoControl + + 14 - - 14, 15 + + 15 - - 42, 13 + + 16 - - 36 + + 17 - - Version + + 18 - - label11 + + 19 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 20 - - groupBoxLocal + + 21 - - 61 + + 22 - - True + + 23 - - NoControl + + 24 - - 18, 50 + + 25 - - 32, 13 + + 26 - - 37 + + 27 - - RSSI + + 28 - - label12 + + 29 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 30 - - groupBoxLocal + + 274, 257 - - 64 + + 80, 21 - - NoControl + + 154 - - 9, 412 + + AES Encryption Level - - 442, 28 + + ENCRYPTION_LEVEL - - 3 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - NOTE: Always click "Copy required to remote" when modifying -this ensures you wont lose radio link + + groupBoxLocal - - lbl_status + + 10 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + False - - $this + + 0 - - 11 + + 1 - - 207, 12 + + 2 - - 102, 20 + + 3 - - 79 + + 4 - - ATI3 + + 5 - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 6 - - groupBoxLocal + + 7 - - 60 + + 8 - - btnRandom + + 9 - - System.Windows.Forms.Button, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 10 - - groupBoxLocal + + 11 - - 0 + + 12 - - lblRX_ENCAP_METHOD + + 13 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 14 - - groupBoxLocal + + 15 - - 1 + + 16 - + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 266, 257 + + + 80, 21 + + + 160 + + + AES Encryption Level + + + RENCRYPTION_LEVEL + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxRemote + + + 10 + + + False + + + 447, 403 + + + 80, 21 + + + 161 + + + The number of output frames for SBUS or PPM missing before enters failsafe. + + + FSFRAMELOSS + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 3 + + + False + + + 447, 403 + + + 80, 21 + + + 167 + + + The number of output frames for SBUS or PPM missing before enters failsafe. + + + RFSFRAMELOSS + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxRemote + + + 3 + + + False + + + NoControl + + + 154, 332 + + + 23, 20 + + + 141 + + + GPO1_3SBUSIN + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 23 + + + False + + + NoControl + + + 148, 332 + + + 36, 20 + + + 149 + + + RGPO1_3SBUSIN + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxRemote + + + 21 + + + False + + + NoControl + + + 154, 382 + + + 23, 20 + + + 151 + + + GPO1_3STATLED + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 13 + + + False + + + NoControl + + + 283, 382 + + + 23, 20 + + + 153 + + + GPO1_0TXEN485 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 11 + + + False + + + NoControl + + + 275, 382 + + + 23, 20 + + + 159 + + + RGPO1_0TXEN485 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxRemote + + + 11 + + + False + + + NoControl + + + 148, 382 + + + 23, 20 + + + 157 + + + RGPO1_3STATLED + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxRemote + + + 13 + + + 60, 12 + + + 147, 20 + + + 33 + + + RTI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxRemote + + + 81 + + + 59, 12 + + + 147, 20 + + + 32 + + + ATI + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 85 + + + True + + + NoControl + + + 14, 15 + + + 42, 13 + + + 36 + + + Version + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 84 + + + True + + + NoControl + + + 18, 50 + + + 32, 13 + + + 37 + + + RSSI + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 87 + + + NoControl + + + 9, 518 + + + 442, 28 + + + 3 + + + NOTE: Always click "Copy required to remote" when modifying +this ensures you wont lose radio link + + + lbl_status + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 10 + + + 207, 12 + + + 102, 20 + + + 79 + + + ATI3 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 83 + + + btnLoadFromFile + + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null + + + groupBoxLocal + + + 0 + + + btnSaveToFile + + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null + + + groupBoxLocal + + + 1 + + + label54 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 2 + + + GPO1_3AUXOUT + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 4 + + + lblGPO1_3AUXOUT + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 5 + + + GPI1_2AUXIN + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 6 + + + lblGPI1_2AUXIN + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 7 + + + lblGPIO1_1FUNC + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 8 + + + GPIO1_1FUNC + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 9 + + + lblGPO1_0TXEN485 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 12 + + + lblGPO1_3STATLED + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 14 + + + GPO1_3SBUSOUT + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 15 + + + label49 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 16 + + + BUT_SetPPMFailSafe + + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null + + + groupBoxLocal + + + 17 + + + txtCountry + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 18 + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 19 + + + RATE_FREQBAND + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 20 + + + lblSBUSOUT + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 21 + + + lblSBUSIN + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 22 + + + btnRandom + + + System.Windows.Forms.Button, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 24 + + + lblRX_ENCAP_METHOD + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 25 + + RX_ENCAP_METHOD - + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 26 + + + lblTX_ENCAP_METHOD + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 27 + + + TX_ENCAP_METHOD + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 28 + + + lblDESTID + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 29 + + + lblNODEID + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 30 + + + DESTID + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 31 + + + NODEID + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 32 + + + lblGPO1_1R_COUT + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 33 + + + lblGPI1_1R_CIN + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 35 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 38 + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 40 + + + FORMAT + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 41 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 43 + + + lblNETID + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 45 + + + lblTXPOWER + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 47 + + + lblECC + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 49 + + + lblOPPRESEND + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 50 + + + lblMAVLINK + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 52 + + + lblANT_MODE + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 53 + + + ANT_MODE + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 2 + + 54 - - lblTX_ENCAP_METHOD + + lblSER_BRK_DETMS - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 3 + + 55 - - TX_ENCAP_METHOD + + lblGLOBAL_RETRIES - + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 56 + + + lblMAX_RETRIES + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 57 + + + SER_BRK_DETMS + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + + groupBoxLocal + + + 58 + + + GLOBAL_RETRIES + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 59 + + + MAX_RETRIES + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 60 + + + MAX_DATA + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 61 + + + lblMAX_DATA + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 62 + + + lblENCRYPTION_LEVEL + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 63 + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 64 + + + txt_aeskey + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 65 + + + lblRTSCTS + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 67 + + + linkLabel_mavlink + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxLocal + + + 68 + + + linkLabel_lowlatency + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxLocal - - 4 + + 69 - - lblDESTID + + lblMAX_WINDOW - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 5 + + 70 - - lblNODEID + + lblMIN_FREQ - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 6 + + 72 - - DESTID + + lblLBT_RSSI - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 7 + + 75 - - NODEID + + lblDUTY_CYCLE - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 8 + + 77 - - label40 + + lblNUM_CHANNELS - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 9 + + 79 - - label39 + + lblMAX_FREQ - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 11 + + 80 - - label2 + + ATI2 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 14 + + 82 - - label1 + + 12, 48 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 533, 463 - + + 80 + + + Local + + groupBoxLocal - - 16 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - FORMAT + + $this - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 6 - - groupBoxLocal + + True - - 17 + + NoControl - - label3 + + 427, 387 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 100, 13 - - groupBoxLocal + + 162 - - 19 + + Failsafe Frame Loss - - label4 + + label54 - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 21 + + 2 - - label5 + + False - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 154, 432 - - 23 + + 23, 20 - - label6 + + 160 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + GPO1_3AUXOUT + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 25 + + 4 + + + True - - label8 + + NoControl - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 18, 436 - - groupBoxLocal + + 93, 13 - - 26 + + 159 + + + GPO1_3AUXOUT - - label7 + + lblGPO1_3AUXOUT - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 28 + + 5 - - lblANT_MODE + + False - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 154, 407 - - 29 + + 23, 20 - - ANT_MODE + + 158 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + GPI1_2AUXIN - + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxLocal - - 30 + + 6 - - lblSER_BRK_DETMS + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 18, 411 - - 31 + + 76, 13 - - lblGLOBAL_RETRIES + + 157 - + + GPI1_2AUXIN + + + lblGPI1_2AUXIN + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 32 + + 7 - - lblMAX_RETRIES + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 182, 411 - - 33 + + 80, 13 - - SER_BRK_DETMS + + 156 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + GPIO1_1FUNC - + + lblGPIO1_1FUNC + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxLocal - - 34 + + 8 - - GLOBAL_RETRIES + + False - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 274, 406 - - groupBoxLocal + + 80, 21 - - 35 + + 155 - - MAX_RETRIES + + GPIO1_1FUNC - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 36 + + 9 - - MAX_DATA + + True - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 182, 386 - - 37 + + 95, 13 - - lblMAX_DATA + + 152 - + + GPO1_0TXEN485 + + + lblGPO1_0TXEN485 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 38 + + 12 - - ENCRYPTION_LEVEL + + True - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 18, 386 - - 39 + + 97, 13 + + + 150 - - label36 + + GPO1_3STATLED - + + lblGPO1_3STATLED + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 40 + + 14 - - label35 + + False - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 425, 332 - - groupBoxLocal + + 102, 21 - - 41 + + 149 - - txt_aeskey + + GPO1_3SBUSOUT - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 42 + + 15 + + + True + + + NoControl + + + 377, 18 + + + 46, 13 + + + 148 - - label19 + + Country: - + + label49 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 44 + + 16 - - linkLabel_mavlink + + 380, 38 - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - - groupBoxLocal + + 61, 39 - - 45 + + 147 - - linkLabel_lowlatency + + txtCountry - - System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 46 + + 18 - - label18 + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 18, 361 - - 47 + + 81, 13 + + + 146 - - label13 + + Rate/FreqBand - + + label45 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 49 + + 19 - - label17 + + False - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 128, 357 - - groupBoxLocal + + 399, 21 - - 52 + + 145 - - label16 + + RATE_FREQBAND - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 54 + + 20 + + + True - - label15 + + NoControl - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 360, 311 - - groupBoxLocal + + 103, 13 - - 56 + + 144 + + + GPO1_3SBUSOUT: - - label14 + + lblSBUSOUT - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 57 + + 21 - - ATI2 + + True - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxLocal + + 18, 336 - - 59 + + 88, 13 - - 12, 48 + + 142 - - 533, 361 + + GPO1_3SBUSIN - - 80 + + lblSBUSIN - - Local + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 + + 22 False @@ -2713,10 +3822,10 @@ this ensures you wont lose radio link NoControl - 242, 291 + 242, 282 - 111, 24 + 113, 24 140 @@ -2734,7 +3843,7 @@ this ensures you wont lose radio link groupBoxLocal - 0 + 24 True @@ -2743,7 +3852,7 @@ this ensures you wont lose radio link NoControl - 360, 196 + 360, 186 58, 13 @@ -2767,13 +3876,13 @@ this ensures you wont lose radio link groupBoxLocal - 1 + 25 False - 447, 193 + 447, 182 80, 21 @@ -2794,7 +3903,7 @@ this ensures you wont lose radio link groupBoxLocal - 2 + 26 True @@ -2803,7 +3912,7 @@ this ensures you wont lose radio link NoControl - 360, 168 + 360, 161 57, 13 @@ -2827,13 +3936,13 @@ this ensures you wont lose radio link groupBoxLocal - 3 + 27 False - 447, 165 + 447, 157 80, 21 @@ -2854,7 +3963,7 @@ this ensures you wont lose radio link groupBoxLocal - 4 + 28 True @@ -2863,7 +3972,7 @@ this ensures you wont lose radio link NoControl - 360, 140 + 360, 136 43, 13 @@ -2887,7 +3996,7 @@ this ensures you wont lose radio link groupBoxLocal - 5 + 29 True @@ -2896,7 +4005,7 @@ this ensures you wont lose radio link NoControl - 360, 112 + 360, 111 47, 13 @@ -2920,13 +4029,13 @@ this ensures you wont lose radio link groupBoxLocal - 6 + 30 False - 447, 137 + 447, 132 80, 21 @@ -2947,13 +4056,13 @@ this ensures you wont lose radio link groupBoxLocal - 7 + 31 False - 447, 109 + 447, 107 80, 21 @@ -2974,67 +4083,67 @@ this ensures you wont lose radio link groupBoxLocal - 8 + 32 - + True - + NoControl - - 18, 326 + + 18, 311 - - 86, 13 + + 91, 13 - + 130 - - GPI1_1R/COUT + + GPO1_1R/COUT - - label40 + + lblGPO1_1R_COUT - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 9 + + 33 - + True - + NoControl - - 18, 300 + + 18, 286 - + 74, 13 - + 128 - + GPI1_1R/CIN - - label39 + + lblGPI1_1R_CIN - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 11 + + 35 True @@ -3043,7 +4152,7 @@ this ensures you wont lose radio link NoControl - 18, 87 + 18, 86 39, 13 @@ -3064,7 +4173,7 @@ this ensures you wont lose radio link groupBoxLocal - 14 + 38 True @@ -3073,7 +4182,7 @@ this ensures you wont lose radio link NoControl - 18, 113 + 18, 111 32, 13 @@ -3094,10 +4203,10 @@ this ensures you wont lose radio link groupBoxLocal - 16 + 40 - 96, 83 + 96, 82 80, 20 @@ -3115,7 +4224,7 @@ this ensures you wont lose radio link groupBoxLocal - 17 + 41 True @@ -3124,7 +4233,7 @@ this ensures you wont lose radio link NoControl - 18, 139 + 18, 136 53, 13 @@ -3145,157 +4254,157 @@ this ensures you wont lose radio link groupBoxLocal - 19 + 43 - + True - + NoControl - - 18, 166 + + 18, 161 - + 38, 13 - + 118 - + Net ID - - label4 + + lblNETID - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 21 + + 45 - + True - + NoControl - - 18, 193 + + 18, 186 - + 52, 13 - + 120 - + Tx Power - - label5 + + lblTXPOWER - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 23 + + 47 - + True - + NoControl - - 18, 218 + + 18, 211 - + 28, 13 - + 122 - + ECC - - label6 + + lblECC - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 25 + + 49 - + True - + NoControl - - 18, 274 + + 18, 261 - + 61, 13 - + 125 - + Op Resend - - label8 + + lblOPPRESEND - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 26 + + 50 - + True - + NoControl - - 18, 247 + + 18, 236 - + 44, 13 - + 123 - + Mavlink - - label7 + + lblMAVLINK - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 28 + + 52 True @@ -3304,7 +4413,7 @@ this ensures you wont lose radio link NoControl - 362, 335 + 360, 86 77, 13 @@ -3315,9 +4424,6 @@ this ensures you wont lose radio link Antenna Mode - - False - lblANT_MODE @@ -3328,13 +4434,13 @@ this ensures you wont lose radio link groupBoxLocal - 29 + 53 False - 447, 335 + 447, 82 80, 21 @@ -3342,9 +4448,6 @@ this ensures you wont lose radio link 109 - - False - ANT_MODE @@ -3355,7 +4458,7 @@ this ensures you wont lose radio link groupBoxLocal - 30 + 54 True @@ -3364,7 +4467,7 @@ this ensures you wont lose radio link NoControl - 360, 310 + 360, 286 84, 13 @@ -3388,7 +4491,7 @@ this ensures you wont lose radio link groupBoxLocal - 31 + 55 True @@ -3397,7 +4500,7 @@ this ensures you wont lose radio link NoControl - 360, 282 + 360, 261 73, 13 @@ -3421,7 +4524,7 @@ this ensures you wont lose radio link groupBoxLocal - 32 + 56 True @@ -3430,7 +4533,7 @@ this ensures you wont lose radio link NoControl - 360, 254 + 360, 236 63, 13 @@ -3454,13 +4557,13 @@ this ensures you wont lose radio link groupBoxLocal - 33 + 57 False - 447, 307 + 447, 282 80, 21 @@ -3481,13 +4584,13 @@ this ensures you wont lose radio link groupBoxLocal - 34 + 58 False - 447, 279 + 447, 257 80, 21 @@ -3508,13 +4611,13 @@ this ensures you wont lose radio link groupBoxLocal - 35 + 59 False - 447, 251 + 447, 232 80, 21 @@ -3535,13 +4638,13 @@ this ensures you wont lose radio link groupBoxLocal - 36 + 60 False - 447, 223 + 447, 207 80, 21 @@ -3562,7 +4665,7 @@ this ensures you wont lose radio link groupBoxLocal - 37 + 61 True @@ -3571,7 +4674,7 @@ this ensures you wont lose radio link NoControl - 360, 226 + 360, 211 53, 13 @@ -3595,64 +4698,37 @@ this ensures you wont lose radio link groupBoxLocal - 38 - - - False - - - NoControl - - - 274, 270 - - - 80, 20 - - - 99 - - - ENCRYPTION_LEVEL - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxLocal - - - 39 + 62 - + True - + NoControl - - 181, 271 + + 181, 261 - + 81, 13 - + 100 - + AES Encryption - - label36 + + lblENCRYPTION_LEVEL - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 40 + + 63 True @@ -3661,7 +4737,7 @@ this ensures you wont lose radio link NoControl - 182, 299 + 182, 286 49, 13 @@ -3682,13 +4758,13 @@ this ensures you wont lose radio link groupBoxLocal - 41 + 64 - 180, 316 + 180, 307 - 32 + 64 174, 20 @@ -3706,37 +4782,37 @@ this ensures you wont lose radio link groupBoxLocal - 42 + 65 - + True - + NoControl - - 181, 217 + + 181, 211 - + 53, 13 - + 97 - + RTS CTS - - label19 + + lblRTSCTS - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 44 + + 67 True @@ -3745,7 +4821,7 @@ this ensures you wont lose radio link NoControl - 183, 333 + 183, 327 146, 13 @@ -3766,7 +4842,7 @@ this ensures you wont lose radio link groupBoxLocal - 45 + 68 True @@ -3775,7 +4851,7 @@ this ensures you wont lose radio link NoControl - 182, 346 + 182, 340 124, 13 @@ -3796,187 +4872,187 @@ this ensures you wont lose radio link groupBoxLocal - 46 + 69 - + True - + NoControl - - 182, 246 + + 182, 236 - + 91, 13 - + 93 - + Max Window (ms) - - label18 + + lblMAX_WINDOW - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 47 + + 70 - + True - + NoControl - + 182, 86 - + 48, 13 - + 87 - + Min Freq - - label13 + + lblMIN_FREQ - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 49 + + 72 - + True - + NoControl - - 182, 191 + + 182, 186 - + 50, 13 - + 91 - + LBT Rssi - - label17 + + lblLBT_RSSI - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 52 + + 75 - + True - + NoControl - - 182, 164 + + 182, 161 - + 58, 13 - + 90 - + Duty Cycle - - label16 + + lblDUTY_CYCLE - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 54 + + 77 - + True - + NoControl - - 182, 138 + + 182, 136 - + 73, 13 - + 89 - + # of Channels - - label15 + + lblNUM_CHANNELS - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 56 + + 79 - + True - + NoControl - - 182, 110 + + 182, 111 - + 51, 13 - + 88 - + Max Freq - - label14 + + lblMAX_FREQ - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxLocal - - 57 + + 80 315, 12 @@ -4000,535 +5076,550 @@ this ensures you wont lose radio link groupBoxLocal - 59 - - - lblRRX_ENCAP_METHOD - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + 82 - - groupBoxRemote + + False - - 0 + + NoControl - - RRX_ENCAP_METHOD + + 209, 428 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 102, 29 - - groupBoxRemote + + 170 - - 1 + + Load from File... - - lblRTX_ENCAP_METHOD + + btnRemoteLoadFromFile - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null - + groupBoxRemote - - 2 - - - RTX_ENCAP_METHOD - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 0 - - groupBoxRemote + + False - - 3 + + NoControl - - lblRDESTID + + 317, 428 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 102, 29 - - groupBoxRemote + + 169 - - 4 + + Save to File... - - lblRNODEID + + btnRemoteSaveToFile - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null - + groupBoxRemote - - 5 - - - RDESTID - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxRemote + + 1 - - 6 + + True - - RNODEID + + NoControl - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 427, 387 - - groupBoxRemote + + 100, 13 - - 7 + + 168 - - label41 + + Failsafe Frame Loss - + + lblRFSFRAMELOSS + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 8 + + 2 - - RFORMAT + + False - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 148, 432 - - 11 + + 23, 20 - - label42 + + 166 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + RGPO1_3AUXOUT - + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxRemote - - 12 + + 4 - - label25 + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 10, 436 - - 17 + + 93, 13 + + + 165 - - label26 + + GPO1_3AUXOUT - + + lblRGPO1_3AUXOUT + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 19 + + 5 - - label27 + + False - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 148, 407 - - 21 + + 23, 20 - - label28 + + 164 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + RGPI1_2AUXIN + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 22 + + 6 + + + True - - label29 + + NoControl - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 10, 411 - - groupBoxRemote + + 76, 13 - - 24 + + 163 - - label32 + + GPI1_2AUXIN - + + lblRGPI1_2AUXIN + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 25 + + 7 - - label30 + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 174, 408 - - 26 + + 80, 13 - - label31 + + 162 - + + GPIO1_1FUNC + + + lblRGPIO1_1FUNC + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 27 + + 8 - - lblRANT_MODE + + False - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 266, 405 - - groupBoxRemote + + 80, 21 - - 28 + + 161 - - RANT_MODE + + RGPIO1_1FUNC - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 29 - - - lblRSER_BRK_DETMS - - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 9 - - groupBoxRemote + + True - - 30 + + NoControl - - lblRGLOBAL_RETRIES + + 174, 386 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 95, 13 - - groupBoxRemote + + 158 - - 31 + + GPO1_0TXEN485 - - lblRMAX_RETRIES + + lblRGPO1_0TXEN485 - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 32 + + 12 - - RSER_BRK_DETMS + + True - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 10, 386 - - 33 + + 97, 13 - - RGLOBAL_RETRIES + + 156 - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + GPO1_3STATLED - + + lblRGPO1_3STATLED + + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxRemote - - 34 + + 14 - - RMAX_RETRIES + + False - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 425, 332 - - groupBoxRemote + + 102, 21 - - 35 + + 155 - - RMAX_DATA + + RGPO1_3SBUSOUT - + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 36 - - - lblRMAX_DATA + + 15 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + False - - groupBoxRemote + + NoControl - - 37 + + 425, 428 - - label38 + + 102, 29 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 87 - - groupBoxRemote + + Set PPM Fail Safe - - 38 + + Record default PPM stream for PPM output (vehicle side) - - RENCRYPTION_LEVEL + + BUT_SetPPMFailSafeRemote - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null - + groupBoxRemote - - 39 - - - txt_Raeskey - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 16 - - groupBoxRemote + + True - - 40 + + NoControl - - label37 + + 364, 18 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 46, 13 - - groupBoxRemote + + 154 - - 41 + + Country: - - label33 + + label50 - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 43 + + 17 - - label34 + + 367, 38 - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + True - - groupBoxRemote + + 61, 39 - - 44 + + 153 - - label24 + + txtRCountry - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 46 + + 18 - - label23 + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 357, 311 - - 52 + + 103, 13 + + + 152 + + + GPO1_3SBUSOUT: - - label22 + + lblRSBUSOUT - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 53 + + 19 - - label21 + + True - - System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 10, 336 - - 54 + + 88, 13 + + + 150 + + + GPO1_3SBUSIN - - label20 + + lblRSBUSIN - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 55 + + 20 - - RTI2 + + True - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl - - groupBoxRemote + + 10, 361 - - 56 + + 81, 13 - - label9 + + 148 - + + Rate/FreqBand + + + label46 + + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 57 + + 22 - - 551, 48 + + False - - 533, 361 + + 121, 357 - - 81 + + 406, 21 - - Remote + + 147 - - groupBoxRemote + + RRATE_FREQBAND - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - $this + + groupBoxRemote - - 6 + + 23 True @@ -4537,7 +5628,7 @@ this ensures you wont lose radio link NoControl - 352, 195 + 357, 186 58, 13 @@ -4561,10 +5652,10 @@ this ensures you wont lose radio link groupBoxRemote - 0 + 24 - 442, 188 + 447, 182 80, 21 @@ -4585,7 +5676,7 @@ this ensures you wont lose radio link groupBoxRemote - 1 + 25 True @@ -4594,7 +5685,7 @@ this ensures you wont lose radio link NoControl - 352, 167 + 357, 161 57, 13 @@ -4618,10 +5709,10 @@ this ensures you wont lose radio link groupBoxRemote - 2 + 26 - 442, 160 + 447, 157 80, 21 @@ -4642,7 +5733,7 @@ this ensures you wont lose radio link groupBoxRemote - 3 + 27 True @@ -4651,7 +5742,7 @@ this ensures you wont lose radio link NoControl - 352, 139 + 357, 136 43, 13 @@ -4675,7 +5766,7 @@ this ensures you wont lose radio link groupBoxRemote - 4 + 28 True @@ -4684,7 +5775,7 @@ this ensures you wont lose radio link NoControl - 352, 111 + 357, 111 47, 13 @@ -4708,10 +5799,10 @@ this ensures you wont lose radio link groupBoxRemote - 5 + 29 - 442, 132 + 447, 132 80, 21 @@ -4732,10 +5823,10 @@ this ensures you wont lose radio link groupBoxRemote - 6 + 30 - 442, 104 + 447, 107 80, 21 @@ -4756,40 +5847,40 @@ this ensures you wont lose radio link groupBoxRemote - 7 + 31 - + True - + NoControl - - 10, 326 + + 10, 311 - - 86, 13 + + 91, 13 - + 121 - - GPI1_1R/COUT + + GPO1_1R/COUT - - label41 + + lblRGPO1_1R_COUT - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 8 + + 32 - 88, 83 + 88, 82 80, 20 @@ -4807,187 +5898,187 @@ this ensures you wont lose radio link groupBoxRemote - 11 + 35 - + True - + NoControl - - 10, 300 + + 10, 286 - + 74, 13 - + 118 - + GPI1_1R/CIN - - label42 + + lblRGPI1_1R_CIN - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 12 + + 36 - + True - + NoControl - - 11, 274 + + 11, 261 - + 61, 13 - + 129 - + Op Resend - - label25 + + lblROPPRESEND - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 17 + + 41 - + True - + NoControl - - 11, 247 + + 11, 236 - + 44, 13 - + 128 - + Mavlink - - label26 + + lblRMAVLINK - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 19 + + 43 - + True - + NoControl - - 11, 220 + + 11, 211 - + 28, 13 - + 127 - + ECC - - label27 + + lblRECC - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 21 + + 45 - + True - + NoControl - - 11, 193 + + 11, 186 - + 52, 13 - + 126 - + Tx Power - - label28 + + lblRTXPOWER - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 22 + + 46 - + True - + NoControl - - 11, 166 + + 11, 161 - + 38, 13 - + 125 - + Net ID - - label29 + + lblRNETID - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 24 + + 48 True @@ -4996,7 +6087,7 @@ this ensures you wont lose radio link NoControl - 11, 113 + 11, 111 32, 13 @@ -5017,7 +6108,7 @@ this ensures you wont lose radio link groupBoxRemote - 25 + 49 True @@ -5026,7 +6117,7 @@ this ensures you wont lose radio link NoControl - 11, 139 + 11, 136 53, 13 @@ -5047,7 +6138,7 @@ this ensures you wont lose radio link groupBoxRemote - 26 + 50 True @@ -5056,7 +6147,7 @@ this ensures you wont lose radio link NoControl - 11, 87 + 11, 86 39, 13 @@ -5077,7 +6168,7 @@ this ensures you wont lose radio link groupBoxRemote - 27 + 51 True @@ -5086,7 +6177,7 @@ this ensures you wont lose radio link NoControl - 354, 332 + 357, 86 77, 13 @@ -5097,9 +6188,6 @@ this ensures you wont lose radio link Antenna Mode - - False - lblRANT_MODE @@ -5110,10 +6198,13 @@ this ensures you wont lose radio link groupBoxRemote - 28 + 52 + + + False - 442, 328 + 447, 82 80, 21 @@ -5121,9 +6212,6 @@ this ensures you wont lose radio link 108 - - False - RANT_MODE @@ -5134,7 +6222,7 @@ this ensures you wont lose radio link groupBoxRemote - 29 + 53 True @@ -5143,7 +6231,7 @@ this ensures you wont lose radio link NoControl - 352, 307 + 357, 286 84, 13 @@ -5167,7 +6255,7 @@ this ensures you wont lose radio link groupBoxRemote - 30 + 54 True @@ -5176,7 +6264,7 @@ this ensures you wont lose radio link NoControl - 352, 279 + 357, 261 73, 13 @@ -5200,7 +6288,7 @@ this ensures you wont lose radio link groupBoxRemote - 31 + 55 True @@ -5209,7 +6297,7 @@ this ensures you wont lose radio link NoControl - 352, 251 + 357, 236 63, 13 @@ -5233,10 +6321,10 @@ this ensures you wont lose radio link groupBoxRemote - 32 + 56 - 442, 300 + 447, 282 80, 21 @@ -5257,10 +6345,10 @@ this ensures you wont lose radio link groupBoxRemote - 33 + 57 - 442, 272 + 447, 257 80, 21 @@ -5281,10 +6369,10 @@ this ensures you wont lose radio link groupBoxRemote - 34 + 58 - 442, 244 + 447, 232 80, 21 @@ -5305,10 +6393,10 @@ this ensures you wont lose radio link groupBoxRemote - 35 + 59 - 442, 216 + 447, 207 80, 21 @@ -5329,7 +6417,7 @@ this ensures you wont lose radio link groupBoxRemote - 36 + 60 True @@ -5338,7 +6426,7 @@ this ensures you wont lose radio link NoControl - 352, 223 + 357, 211 53, 13 @@ -5362,7 +6450,7 @@ this ensures you wont lose radio link groupBoxRemote - 37 + 61 True @@ -5371,7 +6459,7 @@ this ensures you wont lose radio link NoControl - 174, 300 + 174, 286 49, 13 @@ -5392,40 +6480,13 @@ this ensures you wont lose radio link groupBoxRemote - 38 - - - False - - - NoControl - - - 266, 271 - - - 80, 20 - - - 90 - - - RENCRYPTION_LEVEL - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - groupBoxRemote - - - 39 + 62 - 168, 316 + 168, 307 - 32 + 64 180, 20 @@ -5443,247 +6504,247 @@ this ensures you wont lose radio link groupBoxRemote - 40 + 63 - + True - + NoControl - - 173, 272 + + 173, 261 - + 81, 13 - + 92 - + AES Encryption - - label37 + + lblRENCRYPTION_LEVEL - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 41 + + 64 - + True - + NoControl - - 173, 218 + + 173, 211 - + 53, 13 - + 99 - + RTS CTS - - label33 + + lblRRTSCTS - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 43 + + 66 - + True - + NoControl - - 174, 247 + + 174, 236 - + 91, 13 - + 97 - + Max Window (ms) - - label34 + + lblRMAX_WINDOW - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 44 + + 67 - + True - + NoControl - - 174, 87 + + 174, 86 - + 48, 13 - + 87 - + Min Freq - - label24 + + lblRMIN_FREQ - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 46 + + 69 - + True - + NoControl - + 174, 111 - + 51, 13 - + 88 - + Max Freq - - label23 + + lblRMAX_FREQ - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 52 + + 75 - + True - + NoControl - - 174, 139 + + 174, 136 - + 73, 13 - + 89 - + # of Channels - - label22 + + lblRNUM_CHANNELS - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 53 + + 76 - + True - + NoControl - - 174, 165 + + 174, 161 - + 58, 13 - + 93 - + Duty Cycle - - label21 + + lblRDUTY_CYCLE - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 54 + + 77 - + True - + NoControl - - 174, 192 + + 174, 186 - + 50, 13 - + 95 - + LBT Rssi - - label20 + + lblRLBT_RSSI - + System.Windows.Forms.Label, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + groupBoxRemote - - 55 + + 78 300, 12 @@ -5707,7 +6768,7 @@ this ensures you wont lose radio link groupBoxRemote - 56 + 79 True @@ -5737,7 +6798,31 @@ this ensures you wont lose radio link groupBoxRemote - 57 + 80 + + + 551, 48 + + + 533, 463 + + + 81 + + + Remote + + + groupBoxRemote + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 True @@ -5764,40 +6849,19 @@ this ensures you wont lose radio link $this - 5 - - - False - - - NoControl - - - 551, 411 - - - 102, 29 - - - 86 - - - Set PPM Fail Safe - - - Record default PPM stream for PPM output (vehicle side) - - - BUT_SetPPMFailSafe - - - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + 4 - - $this + + 114, 17 + + + INI Files|*.ini - - 1 + + 208, 17 + + + INI Files|*.ini NoControl @@ -5818,13 +6882,13 @@ this ensures you wont lose radio link BUT_loadcustom - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null $this - 2 + 1 NoControl @@ -5845,13 +6909,46 @@ this ensures you wont lose radio link BUT_resettodefault - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null $this - 3 + 2 + + + False + + + NoControl + + + 425, 428 + + + 102, 29 + + + 86 + + + Set PPM Fail Safe + + + Record default PPM stream for PPM output (vehicle side) + + + BUT_SetPPMFailSafe + + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null + + + groupBoxLocal + + + 17 False @@ -5875,13 +6972,13 @@ this ensures you wont lose radio link BUT_savesettings - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null $this - 9 + 8 NoControl @@ -5902,13 +6999,13 @@ this ensures you wont lose radio link BUT_getcurrent - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null $this - 10 + 9 NoControl @@ -5925,17 +7022,20 @@ this ensures you wont lose radio link Upload Firmware (Local) + + False + BUT_upload - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null $this - 12 + 11 False @@ -5944,7 +7044,7 @@ this ensures you wont lose radio link NoControl - 443, 412 + 457, 518 102, 29 @@ -5959,13 +7059,73 @@ this ensures you wont lose radio link BUT_Syncoptions - MissionPlanner.Controls.MyButton, SikRadio, Version=0.0.7428.29620, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null $this - 8 + 7 + + + False + + + NoControl + + + 317, 428 + + + 102, 29 + + + 163 + + + Save to File... + + + btnSaveToFile + + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null + + + groupBoxLocal + + + 1 + + + False + + + NoControl + + + 209, 428 + + + 102, 29 + + + 164 + + + Load from File... + + + btnLoadFromFile + + + MissionPlanner.Controls.MyButton, RFD900Tools, Version=0.2.63.0, Culture=neutral, PublicKeyToken=null + + + groupBoxLocal + + + 0 True @@ -5977,7 +7137,7 @@ this ensures you wont lose radio link 781, 492 - 1096, 492 + 1096, 608 toolTip1 @@ -5985,6 +7145,18 @@ this ensures you wont lose radio link System.Windows.Forms.ToolTip, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + dlgSave + + + System.Windows.Forms.SaveFileDialog, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + dlgOpen + + + System.Windows.Forms.OpenFileDialog, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + Sikradio diff --git a/Radio/Sikradio.zh-Hant.resx b/Radio/Sikradio.zh-Hant.resx index 1fc40fb9c6..00fad60940 100644 --- a/Radio/Sikradio.zh-Hant.resx +++ b/Radio/Sikradio.zh-Hant.resx @@ -117,6 +117,23 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 12, 389 + + + 755, 36 + + + + 2 + + + 17, 17 + + + False + 115 @@ -144,18 +161,75 @@ 1 + + 81, 29 + + + 80, 21 + + + 4 + 鮑率的單位為 kbps. 所以 57 表示為 57600. + + True + + + 3, 32 + + + 32, 13 + + + 5 + 鮑率 + + 81, 3 + + + 80, 20 + + + 7 + + + True + + + 3, 6 + + + 39, 13 + + + 8 + 格式版本 + + True + + + 3, 59 + + + 53, 13 + + + 10 + 速率(空中) + + False + 250 @@ -195,12 +269,36 @@ 2 + + 81, 56 + + + 80, 21 + + + 9 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + True + + + 3, 86 + + + 38, 13 + + + 12 + 網路 ID + + False + 1 @@ -291,12 +389,36 @@ 30 + + 81, 83 + + + 80, 21 + + + 11 + "網路 ID" 由 16 位元組成。這被用於發送跳頻順序並確保資料來自正確的無線電。請確保您和其他人是使用不同的"網路 ID" 除非你想要在同一個區域使用相同網域的無線電。 + + True + + + 3, 113 + + + 52, 13 + + + 14 + 發射功率 + + False + 1 @@ -321,32 +443,128 @@ 20 + + 81, 110 + + + 80, 21 + + + 13 + 發射功率的單位為 dBm。 20dBm 就是 100mW。這個值的設定對於較低階的短距離測試非常有用。 + + True + + + 3, 138 + + + 28, 13 + + + 16 + ECC 校檢 + + False + + + 81, 137 + + + 80, 20 + + + 15 + ECC 是設定啟用/關閉格雷的糾正碼。預設為關閉。如果啟用它你的資料會需要多一倍的字節發送,所以你會損失一半的頻寬,但是它最多能糾正每12位的數據中3位的錯誤。使用於遠距離時通常需配合較低的無線數據傳輸率。格雷解碼每個字節需要20微秒(每位元組則需要40微秒),也就是說在較高的傳輸速率時你的 CPU 會受到限制。所以速率最好不要超過 128kbps。 + + True + + + 3, 167 + + + 44, 13 + + + 18 + Mavlink 協議 + + True + + + 3, 194 + + + 61, 13 + + + 20 + 伺機重送 + + False + + + 81, 191 + + + 80, 20 + + + 19 + - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + False + + + 83, 191 + + + 80, 20 + + + 29 + - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + False + + + 83, 137 + + + 80, 20 + + + 27 + ECC 是設定啟用/關閉格雷的糾正碼。預設為關閉。如果啟用它你的資料會需要多一倍的字節發送,所以你會損失一半的頻寬,但是它最多能糾正每12位的數據中3位的錯誤。使用於遠距離時通常需配合較低的無線數據傳輸率。格雷解碼每個字節需要20微秒(每位元組則需要40微秒),也就是說在較高的傳輸速率時你的 CPU 會受到限制。所以速率最好不要超過 128kbps。 + + False + 1 @@ -371,10 +589,22 @@ 20 + + 83, 110 + + + 80, 21 + + + 26 + - 發射功率的單位為 dBm。 20dBm 就是 100mW。這個值的設定對於較低階的短距離測試非常有用。 + 發射功率的單位為 dBm。 20dBm 就是 100mW。這個值的設定對於較低階的短距離測試非常有用。 + + False + 1 @@ -465,9 +695,21 @@ 30 + + 83, 83 + + + 80, 21 + + + 25 + "網路 ID" 由 16 位元組成。這被用於發送跳頻順序並確保資料來自正確的無線電。請確保您和其他人是使用不同的"網路 ID" 除非你想要在同一個區域使用相同網域的無線電。 + + False + 250 @@ -507,9 +749,21 @@ 2 + + 83, 56 + + + 80, 21 + + + 24 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + False + 115 @@ -537,20 +791,44 @@ 1 + + 83, 29 + + + 80, 21 + + + 22 + - 鮑率的單位為 kbps. 所以 57 表示為 57600. + 鮑率的單位為 kbps. 所以 57 表示為 57600. + + 59, 38 + + + True + + + 250, 39 + + + 34 + - see the spec for a RSSI to dBm graph. The numbers at the end are: -txe: 發射端錯誤代碼 (eg. transmit timeouts) -rxe: 接收端錯誤代碼 (crc error, framing error etc) -stx: 發射端溢位錯誤代碼 -rrx: 接收端溢位錯誤代碼 -ecc: number of 12 bit words successfully corrected by the golay code -which result in a valid packet CRC + see the spec for a RSSI to dBm graph. The numbers at the end are: +txe: 發射端錯誤代碼 (eg. transmit timeouts) +rxe: 接收端錯誤代碼 (crc error, framing error etc) +stx: 發射端溢位錯誤代碼 +rrx: 接收端溢位錯誤代碼 +ecc: number of 12 bit words successfully corrected by the golay code +which result in a valid packet CRC + + False + 5 @@ -608,9 +886,21 @@ which result in a valid packet CRC 50 + + 96, 55 + + + 80, 21 + + + 42 + 跳頻的頻道數 + + False + 10 @@ -641,27 +931,63 @@ which result in a valid packet CRC 100 + + 96, 82 + + + 80, 21 + + + 43 + 允許傳送的時間百分比 + + False + 0 25 + + 96, 109 + + + 80, 21 + + + 44 + 先接收後傳送 + + False + 0 25 + + 97, 109 + + + 80, 21 + + + 56 + 先接收後傳送 + + False + 10 @@ -692,9 +1018,21 @@ which result in a valid packet CRC 100 + + 97, 82 + + + 80, 21 + + + 55 + 允許傳送的時間百分比 + + False + 5 @@ -752,9 +1090,21 @@ which result in a valid packet CRC 50 + + 97, 55 + + + 80, 21 + + + 54 + 跳頻的頻道數 + + False + 902000 @@ -782,9 +1132,21 @@ which result in a valid packet CRC 435000 + + 96, 28 + + + 80, 21 + + + 41 + 終止頻率的單位 kHz + + False + 902000 @@ -821,9 +1183,21 @@ which result in a valid packet CRC + + 96, 3 + + + 80, 21 + + + 46 + 起始頻率的單位 kHz + + False + 902000 @@ -851,9 +1225,21 @@ which result in a valid packet CRC 435000 + + 97, 3 + + + 80, 21 + + + 58 + 起始頻率的單位 kHz + + False + 902000 @@ -881,19 +1267,43 @@ which result in a valid packet CRC 435000 + + 97, 28 + + + 80, 21 + + + 53 + 終止頻率的單位 kHz + + True + + + 689, 11 + + + 63, 13 + + + 83 + Led 狀態說明 - 3DR 數傳有 2 個狀態指示燈, 一紅一綠。 -綠色 LED 閃爍 - 尋找另一個數傳中 -綠色 LED 恆亮 - 已連結另一個數傳 -紅色 LED 閃爍 - 資料傳輸中 + 3DR 數傳有 2 個狀態指示燈, 一紅一綠。 +綠色 LED 閃爍 - 尋找另一個數傳中 +綠色 LED 恆亮 - 已連結另一個數傳 +紅色 LED 閃爍 - 資料傳輸中 紅色 LED 恆亮 - 韌體更新中 + + False + 0 @@ -987,9 +1397,21 @@ which result in a valid packet CRC 30 + + 96, 164 + + + 80, 21 + + + 52 + 節點 ID。預設 ID 為 0。在多點作業的環境需要有一點為基礎點 。 + + False + 0 @@ -1083,124 +1505,800 @@ which result in a valid packet CRC 30 + + 97, 164 + + + 80, 21 + + + 64 + 節點 ID。預設 ID 為 0。在多點作業的環境需要有一點為基礎點 。 + + False + + + 81, 164 + + + 80, 21 + + + 21 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + False + + + 83, 163 + + + 80, 21 + + + 22 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + False + + + + NoControl + + + 96, 136 + + + 80, 20 + + + 56 + 開啟或關閉硬體流量控制 + + False + + + NoControl + + + 97, 136 + + + 80, 20 + + + 66 + 開啟或關閉硬體流量控制 + + 83, 3 + + + 80, 20 + + + 23 + + + 138, 12 + + + 102, 20 + + + 33 + + + 59, 12 + + + 147, 20 + + + 32 + + + True + + + 14, 15 + + + 42, 13 + + + 36 + 韌體版本 + + True + + + 18, 50 + + + 32, 13 + + + 37 + 信號強度 + + False + + + 237, 3 + + + 69, 39 + + + 21 + 儲存設定 + + 162, 3 + + + 69, 39 + + + 6 + 載入設定 + + 12, 361 + + + 310, 22 + + + 3 + + + 312, 3 + + + 121, 39 + + + 0 + 更新韌體 (地面端) + + True + + + NoControl + + + 4, 6 + + + 48, 13 + + + 47 + 跳頻 起始頻率 + + True + + + NoControl + + + 4, 31 + + + 51, 13 + + + 48 + 跳頻 終止頻率 + + True + + + NoControl + + + 4, 58 + + + 73, 13 + + + 49 + 跳頻 頻道數 + + True + + + NoControl + + + 4, 85 + + + 58, 13 + + + 50 + 允許發射時間% + + True + + + NoControl + + + 4, 112 + + + 50, 13 + + + 51 + 避開已用頻率 + + True + + + NoControl + + + 5, 112 + + + 50, 13 + + + 63 + 避開已用頻率 + + True + + + NoControl + + + 5, 85 + + + 58, 13 + + + 62 + 允許發射時間% + + True + + + NoControl + + + 5, 58 + + + 73, 13 + + + 61 + 跳頻 頻道數 + + True + + + NoControl + + + 5, 31 + + + 51, 13 + + + 60 + 跳頻 終止頻率 + + True + + + NoControl + + + 5, 6 + + + 48, 13 + + + 59 + 跳頻 起始頻率 + + True + + + NoControl + + + 6, 199 + + + 61, 13 + + + 72 + 伺機重送 + + True + + + NoControl + + + 6, 167 + + + 44, 13 + + + 71 + Mavlink 協議 + + True + + + NoControl + + + 6, 140 + + + 28, 13 + + + 70 + ECC 校檢 + + True + + + NoControl + + + 6, 113 + + + 52, 13 + + + 69 + 發射功率 + + True + + + NoControl + + + 6, 86 + + + 38, 13 + + + 68 + 網路 ID + + True + + + NoControl + + + 6, 59 + + + 53, 13 + + + 67 + 速率(空中) + + True + + + NoControl + + + 6, 6 + + + 39, 13 + + + 66 + 格式版本 + + True + + + NoControl + + + 6, 32 + + + 32, 13 + + + 65 + 鮑率 + + True + + + 4, 81 + + + True + + + NoControl + + + 3, 138 + + + 53, 13 + + + 57 + 流量管制 + + True + + + NoControl + + + 7, 189 + + + 146, 13 + + + 55 + 重設為標準 Mavlink 協議 + + True + + + 7, 202 + + + 124, 13 + + + 54 + 重設為最小延遲 + + True + + + NoControl + + + 4, 167 + + + 91, 13 + + + 53 + 最大窗口 (ms) + + 374, 221 + + + 172 + + + 1 + + + 0 + + + True + + + 4, 81 + + + True + + + NoControl + + + 4, 138 + + + 53, 13 + + + 67 + 流量管制 + + True + + + NoControl + + + 5, 167 + + + 91, 13 + + + 65 + 最大窗口 (ms) + + 357, 221 + + + 170 + + + 1 + + + 0 + + + False + + + NoControl + + + 346, 355 + + + 102, 29 + + + 78 + 複製設定至機上端 + + 207, 12 + + + 102, 20 + + + 79 + + + 12, 48 + + + 382, 306 + + + 80 + 地面端 + + 315, 12 + + + True + + + 61, 65 + + + 80 + + + 400, 48 + + + 367, 306 + + + 81 + 機上端 + + 246, 12 + + + True + + + 61, 65 + + + 81 + + + True + + + NoControl + + + 12, 15 + + + 42, 13 + + + 37 + 韌體版本 + + True + + + NoControl + + + 9, 11 + + + 0, 13 + + + 82 + + + NoControl + + + 439, 3 + + + 82, 39 + + + 84 + 還原出廠值 + + NoControl + + + 527, 3 + + + 96, 39 + + + 85 + 更新客制化韌體 + + True + + + 6, 13 + + + 781, 433 + \ No newline at end of file diff --git a/Radio/Sikradio.zh-TW.resx b/Radio/Sikradio.zh-TW.resx index 1fc40fb9c6..00fad60940 100644 --- a/Radio/Sikradio.zh-TW.resx +++ b/Radio/Sikradio.zh-TW.resx @@ -117,6 +117,23 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 12, 389 + + + 755, 36 + + + + 2 + + + 17, 17 + + + False + 115 @@ -144,18 +161,75 @@ 1 + + 81, 29 + + + 80, 21 + + + 4 + 鮑率的單位為 kbps. 所以 57 表示為 57600. + + True + + + 3, 32 + + + 32, 13 + + + 5 + 鮑率 + + 81, 3 + + + 80, 20 + + + 7 + + + True + + + 3, 6 + + + 39, 13 + + + 8 + 格式版本 + + True + + + 3, 59 + + + 53, 13 + + + 10 + 速率(空中) + + False + 250 @@ -195,12 +269,36 @@ 2 + + 81, 56 + + + 80, 21 + + + 9 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + True + + + 3, 86 + + + 38, 13 + + + 12 + 網路 ID + + False + 1 @@ -291,12 +389,36 @@ 30 + + 81, 83 + + + 80, 21 + + + 11 + "網路 ID" 由 16 位元組成。這被用於發送跳頻順序並確保資料來自正確的無線電。請確保您和其他人是使用不同的"網路 ID" 除非你想要在同一個區域使用相同網域的無線電。 + + True + + + 3, 113 + + + 52, 13 + + + 14 + 發射功率 + + False + 1 @@ -321,32 +443,128 @@ 20 + + 81, 110 + + + 80, 21 + + + 13 + 發射功率的單位為 dBm。 20dBm 就是 100mW。這個值的設定對於較低階的短距離測試非常有用。 + + True + + + 3, 138 + + + 28, 13 + + + 16 + ECC 校檢 + + False + + + 81, 137 + + + 80, 20 + + + 15 + ECC 是設定啟用/關閉格雷的糾正碼。預設為關閉。如果啟用它你的資料會需要多一倍的字節發送,所以你會損失一半的頻寬,但是它最多能糾正每12位的數據中3位的錯誤。使用於遠距離時通常需配合較低的無線數據傳輸率。格雷解碼每個字節需要20微秒(每位元組則需要40微秒),也就是說在較高的傳輸速率時你的 CPU 會受到限制。所以速率最好不要超過 128kbps。 + + True + + + 3, 167 + + + 44, 13 + + + 18 + Mavlink 協議 + + True + + + 3, 194 + + + 61, 13 + + + 20 + 伺機重送 + + False + + + 81, 191 + + + 80, 20 + + + 19 + - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + False + + + 83, 191 + + + 80, 20 + + + 29 + - OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands. + + False + + + 83, 137 + + + 80, 20 + + + 27 + ECC 是設定啟用/關閉格雷的糾正碼。預設為關閉。如果啟用它你的資料會需要多一倍的字節發送,所以你會損失一半的頻寬,但是它最多能糾正每12位的數據中3位的錯誤。使用於遠距離時通常需配合較低的無線數據傳輸率。格雷解碼每個字節需要20微秒(每位元組則需要40微秒),也就是說在較高的傳輸速率時你的 CPU 會受到限制。所以速率最好不要超過 128kbps。 + + False + 1 @@ -371,10 +589,22 @@ 20 + + 83, 110 + + + 80, 21 + + + 26 + - 發射功率的單位為 dBm。 20dBm 就是 100mW。這個值的設定對於較低階的短距離測試非常有用。 + 發射功率的單位為 dBm。 20dBm 就是 100mW。這個值的設定對於較低階的短距離測試非常有用。 + + False + 1 @@ -465,9 +695,21 @@ 30 + + 83, 83 + + + 80, 21 + + + 25 + "網路 ID" 由 16 位元組成。這被用於發送跳頻順序並確保資料來自正確的無線電。請確保您和其他人是使用不同的"網路 ID" 除非你想要在同一個區域使用相同網域的無線電。 + + False + 250 @@ -507,9 +749,21 @@ 2 + + 83, 56 + + + 80, 21 + + + 24 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + False + 115 @@ -537,20 +791,44 @@ 1 + + 83, 29 + + + 80, 21 + + + 22 + - 鮑率的單位為 kbps. 所以 57 表示為 57600. + 鮑率的單位為 kbps. 所以 57 表示為 57600. + + 59, 38 + + + True + + + 250, 39 + + + 34 + - see the spec for a RSSI to dBm graph. The numbers at the end are: -txe: 發射端錯誤代碼 (eg. transmit timeouts) -rxe: 接收端錯誤代碼 (crc error, framing error etc) -stx: 發射端溢位錯誤代碼 -rrx: 接收端溢位錯誤代碼 -ecc: number of 12 bit words successfully corrected by the golay code -which result in a valid packet CRC + see the spec for a RSSI to dBm graph. The numbers at the end are: +txe: 發射端錯誤代碼 (eg. transmit timeouts) +rxe: 接收端錯誤代碼 (crc error, framing error etc) +stx: 發射端溢位錯誤代碼 +rrx: 接收端溢位錯誤代碼 +ecc: number of 12 bit words successfully corrected by the golay code +which result in a valid packet CRC + + False + 5 @@ -608,9 +886,21 @@ which result in a valid packet CRC 50 + + 96, 55 + + + 80, 21 + + + 42 + 跳頻的頻道數 + + False + 10 @@ -641,27 +931,63 @@ which result in a valid packet CRC 100 + + 96, 82 + + + 80, 21 + + + 43 + 允許傳送的時間百分比 + + False + 0 25 + + 96, 109 + + + 80, 21 + + + 44 + 先接收後傳送 + + False + 0 25 + + 97, 109 + + + 80, 21 + + + 56 + 先接收後傳送 + + False + 10 @@ -692,9 +1018,21 @@ which result in a valid packet CRC 100 + + 97, 82 + + + 80, 21 + + + 55 + 允許傳送的時間百分比 + + False + 5 @@ -752,9 +1090,21 @@ which result in a valid packet CRC 50 + + 97, 55 + + + 80, 21 + + + 54 + 跳頻的頻道數 + + False + 902000 @@ -782,9 +1132,21 @@ which result in a valid packet CRC 435000 + + 96, 28 + + + 80, 21 + + + 41 + 終止頻率的單位 kHz + + False + 902000 @@ -821,9 +1183,21 @@ which result in a valid packet CRC + + 96, 3 + + + 80, 21 + + + 46 + 起始頻率的單位 kHz + + False + 902000 @@ -851,9 +1225,21 @@ which result in a valid packet CRC 435000 + + 97, 3 + + + 80, 21 + + + 58 + 起始頻率的單位 kHz + + False + 902000 @@ -881,19 +1267,43 @@ which result in a valid packet CRC 435000 + + 97, 28 + + + 80, 21 + + + 53 + 終止頻率的單位 kHz + + True + + + 689, 11 + + + 63, 13 + + + 83 + Led 狀態說明 - 3DR 數傳有 2 個狀態指示燈, 一紅一綠。 -綠色 LED 閃爍 - 尋找另一個數傳中 -綠色 LED 恆亮 - 已連結另一個數傳 -紅色 LED 閃爍 - 資料傳輸中 + 3DR 數傳有 2 個狀態指示燈, 一紅一綠。 +綠色 LED 閃爍 - 尋找另一個數傳中 +綠色 LED 恆亮 - 已連結另一個數傳 +紅色 LED 閃爍 - 資料傳輸中 紅色 LED 恆亮 - 韌體更新中 + + False + 0 @@ -987,9 +1397,21 @@ which result in a valid packet CRC 30 + + 96, 164 + + + 80, 21 + + + 52 + 節點 ID。預設 ID 為 0。在多點作業的環境需要有一點為基礎點 。 + + False + 0 @@ -1083,124 +1505,800 @@ which result in a valid packet CRC 30 + + 97, 164 + + + 80, 21 + + + 64 + 節點 ID。預設 ID 為 0。在多點作業的環境需要有一點為基礎點 。 + + False + + + 81, 164 + + + 80, 21 + + + 21 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + False + + + 83, 163 + + + 80, 21 + + + 22 + 速率是無線資料傳輸率單位為 kbps。128 表示 128kbps。 最大值為 192,最小值為 2。我不建議這個頻率低於 16 這樣會造成 tdm 同步時間太久。 + + False + + + + NoControl + + + 96, 136 + + + 80, 20 + + + 56 + 開啟或關閉硬體流量控制 + + False + + + NoControl + + + 97, 136 + + + 80, 20 + + + 66 + 開啟或關閉硬體流量控制 + + 83, 3 + + + 80, 20 + + + 23 + + + 138, 12 + + + 102, 20 + + + 33 + + + 59, 12 + + + 147, 20 + + + 32 + + + True + + + 14, 15 + + + 42, 13 + + + 36 + 韌體版本 + + True + + + 18, 50 + + + 32, 13 + + + 37 + 信號強度 + + False + + + 237, 3 + + + 69, 39 + + + 21 + 儲存設定 + + 162, 3 + + + 69, 39 + + + 6 + 載入設定 + + 12, 361 + + + 310, 22 + + + 3 + + + 312, 3 + + + 121, 39 + + + 0 + 更新韌體 (地面端) + + True + + + NoControl + + + 4, 6 + + + 48, 13 + + + 47 + 跳頻 起始頻率 + + True + + + NoControl + + + 4, 31 + + + 51, 13 + + + 48 + 跳頻 終止頻率 + + True + + + NoControl + + + 4, 58 + + + 73, 13 + + + 49 + 跳頻 頻道數 + + True + + + NoControl + + + 4, 85 + + + 58, 13 + + + 50 + 允許發射時間% + + True + + + NoControl + + + 4, 112 + + + 50, 13 + + + 51 + 避開已用頻率 + + True + + + NoControl + + + 5, 112 + + + 50, 13 + + + 63 + 避開已用頻率 + + True + + + NoControl + + + 5, 85 + + + 58, 13 + + + 62 + 允許發射時間% + + True + + + NoControl + + + 5, 58 + + + 73, 13 + + + 61 + 跳頻 頻道數 + + True + + + NoControl + + + 5, 31 + + + 51, 13 + + + 60 + 跳頻 終止頻率 + + True + + + NoControl + + + 5, 6 + + + 48, 13 + + + 59 + 跳頻 起始頻率 + + True + + + NoControl + + + 6, 199 + + + 61, 13 + + + 72 + 伺機重送 + + True + + + NoControl + + + 6, 167 + + + 44, 13 + + + 71 + Mavlink 協議 + + True + + + NoControl + + + 6, 140 + + + 28, 13 + + + 70 + ECC 校檢 + + True + + + NoControl + + + 6, 113 + + + 52, 13 + + + 69 + 發射功率 + + True + + + NoControl + + + 6, 86 + + + 38, 13 + + + 68 + 網路 ID + + True + + + NoControl + + + 6, 59 + + + 53, 13 + + + 67 + 速率(空中) + + True + + + NoControl + + + 6, 6 + + + 39, 13 + + + 66 + 格式版本 + + True + + + NoControl + + + 6, 32 + + + 32, 13 + + + 65 + 鮑率 + + True + + + 4, 81 + + + True + + + NoControl + + + 3, 138 + + + 53, 13 + + + 57 + 流量管制 + + True + + + NoControl + + + 7, 189 + + + 146, 13 + + + 55 + 重設為標準 Mavlink 協議 + + True + + + 7, 202 + + + 124, 13 + + + 54 + 重設為最小延遲 + + True + + + NoControl + + + 4, 167 + + + 91, 13 + + + 53 + 最大窗口 (ms) + + 374, 221 + + + 172 + + + 1 + + + 0 + + + True + + + 4, 81 + + + True + + + NoControl + + + 4, 138 + + + 53, 13 + + + 67 + 流量管制 + + True + + + NoControl + + + 5, 167 + + + 91, 13 + + + 65 + 最大窗口 (ms) + + 357, 221 + + + 170 + + + 1 + + + 0 + + + False + + + NoControl + + + 346, 355 + + + 102, 29 + + + 78 + 複製設定至機上端 + + 207, 12 + + + 102, 20 + + + 79 + + + 12, 48 + + + 382, 306 + + + 80 + 地面端 + + 315, 12 + + + True + + + 61, 65 + + + 80 + + + 400, 48 + + + 367, 306 + + + 81 + 機上端 + + 246, 12 + + + True + + + 61, 65 + + + 81 + + + True + + + NoControl + + + 12, 15 + + + 42, 13 + + + 37 + 韌體版本 + + True + + + NoControl + + + 9, 11 + + + 0, 13 + + + 82 + + + NoControl + + + 439, 3 + + + 82, 39 + + + 84 + 還原出廠值 + + NoControl + + + 527, 3 + + + 96, 39 + + + 85 + 更新客制化韌體 + + True + + + 6, 13 + + + 781, 433 + \ No newline at end of file diff --git a/Radio/Uploader.cs b/Radio/Uploader.cs index cb1609121c..e4395bf678 100644 --- a/Radio/Uploader.cs +++ b/Radio/Uploader.cs @@ -24,6 +24,9 @@ public enum Board : byte DEVICE_ID_RFD900U = 0X80 | 0x01, DEVICE_ID_RFD900P = 0x80 | 0x02, DEVICE_ID_RFD900X = 0x80 | 0x03, + DEVICE_ID_RFD900X2 = 0x80 | 0x04, + DEVICE_ID_RFD900UX2 = 0x80 | 0x05, + DEVICE_ID_RFD900UX = 0x80 | 0x08, FAILED = 0x11 diff --git a/Radio/XModem.cs b/Radio/XModem.cs index 027de004aa..90b81ea475 100644 --- a/Radio/XModem.cs +++ b/Radio/XModem.cs @@ -54,75 +54,135 @@ public static void SendBlock(FileStream fs, ICommsSerial Serial, int bNumber) var bytesRead = fs.Read(bits, 0, bits.Length); - if (bytesRead == bits.Length) - { - CRC = CRC_calc(bits, 128); - System.Buffer.BlockCopy(bits, 0, packet, 3, 128); - packet[131] = (byte)(CRC >> 8); - packet[132] = (byte)(CRC); - Serial.Write(packet, 0, packet.Length); - } - else if (bytesRead > 0) + CRC = CRC_calc(bits, 128); + System.Buffer.BlockCopy(bits, 0, packet, 3, 128); + packet[131] = (byte)(CRC >> 8); + packet[132] = (byte)(CRC); + Serial.Write(packet, 0, packet.Length); + } + + /// + /// + /// + /// Must be no more than 128 bytes in length. Must not be null. + /// + /// + public static void SendBlock(byte[] data, int DataLength, ICommsSerial Serial, int bNumber) + { + byte[] packet = new byte[133]; + byte[] bits = new byte[128]; + UInt16 CRC = 0; + + for (int i = 0; i < bits.Length; i++) { bits[i] = 0x26; } + + packet[0] = SOH; + packet[1] = (byte)(bNumber % 256); + packet[2] = (byte)(255 - (bNumber % 256)); + + Array.Copy(data, bits, DataLength); + + CRC = CRC_calc(bits, 128); + System.Buffer.BlockCopy(bits, 0, packet, 3, 128); + packet[131] = (byte)(CRC >> 8); + packet[132] = (byte)(CRC); + Serial.DiscardInBuffer(); + Serial.Write(packet, 0, packet.Length); + } + + static void SendEOT(ICommsSerial Serial) + { + Serial.Write(new byte[] { EOT }, 0, 1); + ProgressEvent?.Invoke(100); + } + + static bool UploadBlock(ICommsSerial comPort, byte[] Data, int DataLength, int bNumber) + { + for (int Retry = 0; Retry < 10; Retry++) { - CRC = CRC_calc(bits, 128); - System.Buffer.BlockCopy(bits, 0, packet, 3, 128); - packet[131] = (byte)(CRC >> 8); - packet[132] = (byte)(CRC); - Serial.Write(packet, 0, packet.Length); - Serial.Write(new byte[] { EOT }, 0, 1); - ProgressEvent?.Invoke(100); + //comPort.DiscardInBuffer(); + SendBlock(Data, DataLength, comPort, bNumber); + // responce ACK + var ack = comPort.ReadByte(); + while (ack == 'C') + { + ack = comPort.ReadByte(); + } + + if (ack == ACK) + { + return true; + } + + //Thread.Sleep(1000); } - else if (bytesRead == 0) + + return false; + } + + static bool UploadEnd(ICommsSerial comPort) + { + for (int Retry = 0; Retry < 10; Retry++) { - Serial.Write(new byte[] { EOT }, 0, 1); - ProgressEvent?.Invoke(100); + SendEOT(comPort); + + var ack = comPort.ReadByte(); + while (ack == 'C') + ack = comPort.ReadByte(); + + if (ack == ACK) + { + return true; + } + + //Thread.Sleep(1000); } + + /*MsgBox.CustomMessageBox.Show("Corrupted packet. Please power cycle and try again.\r\n", "Warning", + MessageBoxButtons.OK, MessageBoxIcon.Warning);*/ + return false; } - public static void Upload(string firmwarebin, ICommsSerial comPort) + public static bool Upload(string firmwarebin, ICommsSerial comPort) { comPort.ReadTimeout = 2000; - using (var fs = new FileStream(firmwarebin, FileMode.Open)) + using (var fs = new FileStream(firmwarebin, FileMode.OpenOrCreate,FileAccess.Read)) { var len = (int)fs.Length; len = (len % 128) == 0 ? len / 128 : (len / 128) + 1; var startlen = len; int a = 1; - int NoAckCount = 0; while (len > 0) { LogEvent?.Invoke("Uploading block " + a + "/" + startlen); - SendBlock(fs, comPort, a); - // responce ACK - var ack = comPort.ReadByte(); - while (ack == 'C') - ack = comPort.ReadByte(); + byte[] Data = new byte[128]; - if (ack == ACK) + var bytesRead = fs.Read(Data, 0, Data.Length); + + if (UploadBlock(comPort, Data, bytesRead, a)) { - NoAckCount = 0; len--; a++; - ProgressEvent?.Invoke(1 - ((double)len / (double)startlen)); } - else if (ack == NAK) - { - MsgBox.CustomMessageBox.Show("Corrupted packet. Please power cycle and try again.\r\n", "Warning", - MessageBoxButtons.OK, MessageBoxIcon.Warning); - len = 0; - } else { - NoAckCount++; - if (NoAckCount >= 10) - { - } + /*MsgBox.CustomMessageBox.Show("Corrupted packet. Please power cycle and try again.\r\n", "Warning", + MessageBoxButtons.OK, MessageBoxIcon.Warning);*/ + len = 0; + + return false; } } + + if (!UploadEnd(comPort)) + { + return false; + } + + //Console.WriteLine("Finished " + len.ToString()); } // boot @@ -131,6 +191,8 @@ public static void Upload(string firmwarebin, ICommsSerial comPort) Thread.Sleep(100); comPort.Write("BOOTNEW\r\n"); Thread.Sleep(100); + + return true; } } } diff --git a/SerialOptionRules.json b/SerialOptionRules.json index 73ae39e81e..d4bd0be3e3 100644 --- a/SerialOptionRules.json +++ b/SerialOptionRules.json @@ -8,15 +8,5 @@ "PresetBaudRate": -1, "PresetOptionsByte": 0, "Comment": "If connecting a Mavlink sensor, consider setting 'Do not forward Mavlink to/from'" - }, - "10": { - "PresetBaudRate": -1, - "PresetOptionsByte": 7, - "Comment": "If not using inverter, remove 'Half Duplex' if not a H7 board remove 'invert Tx/RX' and add 'Pullup' if neccessary" - }, - "23": { - "PresetBaudRate": -1, - "PresetOptionsByte": 7, - "Comment": "If not using inverter, remove 'Half Duplex' if not a H7 board remove 'invert Tx/RX' and add 'Pullup' if neccessary" } -} \ No newline at end of file +} diff --git a/SikRadio/ComPort.cs b/SikRadio/ComPort.cs new file mode 100644 index 0000000000..5dd3ce8ef1 --- /dev/null +++ b/SikRadio/ComPort.cs @@ -0,0 +1,18 @@ +using System; +using MissionPlanner.Comms; + +namespace MissionPlanner.Radio +{ + public static class ComPort + { + public static ICommsSerial GetComPortForSiKRadio() + { + return SikRadio.Config.comPort; + } + + public static void FinishedWithComPortForSiKRadio() + { + } + } + +} \ No newline at end of file diff --git a/SikRadio/Config.cs b/SikRadio/Config.cs index d11c1cf25d..898307b654 100644 --- a/SikRadio/Config.cs +++ b/SikRadio/Config.cs @@ -64,7 +64,7 @@ private ISikRadioForm loadSettings() var form = new Sikradio(); form.Enabled = false; - form.GetCommsSerialAlt = () => SikRadio.Config.comPort; + form.DoDisconnectReconnect += DoDisconnectReconnect; panel1.Controls.Add(form); @@ -113,6 +113,15 @@ private ISikRadioForm loadRssi() return form; } + void DoDisconnectReconnect() + { + if (_Connected) + { + Disconnect(); + Connect(); + } + } + private void CMB_SerialPort_SelectedIndexChanged(object sender, EventArgs e) { MainV2.comPort.BaseStream.PortName = CMB_SerialPort.Text; @@ -152,6 +161,7 @@ void ShowForm(Func Constructor) } _CurrentForm = Constructor(); _CurrentForm.Enabled = _Connected; + groupBox2.Text = _CurrentForm.Header; _CurrentForm.Show(); if (_Connected) { @@ -174,53 +184,9 @@ private void rssiToolStripMenuItem_Click(object sender, EventArgs e) ShowForm(loadRssi); } - void getTelemPortWithRadio(ref ICommsSerial comPort) - { - // try telem1 - - comPort = new MAVLinkSerialPort(MainV2.comPort, (int)MAVLink.SERIAL_CONTROL_DEV.TELEM1); - - comPort.ReadTimeout = 4000; - - comPort.Open(); - } - bool Connect() { - try - { - if (MainV2.comPort.BaseStream.PortName.Contains("TCP")) - { - _comPort = new TcpSerial(); - _comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate; - _comPort.ReadTimeout = 4000; - _comPort.Open(); - } - else - { - _comPort = new SerialPort(); - - if (MainV2.comPort.BaseStream.IsOpen) - { - getTelemPortWithRadio(ref _comPort); - } - else - { - _comPort.PortName = MainV2.comPort.BaseStream.PortName; - _comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate; - } - - _comPort.ReadTimeout = 4000; - - _comPort.Open(); - } - - return true; - } - catch - { - return false; - } + return Sikradio.Connect(ref _comPort); } bool Disconnect() diff --git a/SikRadio/Config.resx b/SikRadio/Config.resx index ee1684c823..16a68d4a7e 100644 --- a/SikRadio/Config.resx +++ b/SikRadio/Config.resx @@ -205,7 +205,7 @@ 781, 433 - 1127, 502 + 1127, 622 2 @@ -313,7 +313,7 @@ 12, 108 - 1132, 527 + 1132, 631 8 @@ -454,7 +454,7 @@ 42 - 1156, 639 + 1156, 743 diff --git a/SikRadio/ISikRadioForm.cs b/SikRadio/ISikRadioForm.cs index eeab6dc8ef..ec67d03385 100644 --- a/SikRadio/ISikRadioForm.cs +++ b/SikRadio/ISikRadioForm.cs @@ -8,5 +8,6 @@ public interface ISikRadioForm : IDisposable void Disconnect(); void Show(); bool Enabled { get; set; } + string Header { get; } } } \ No newline at end of file diff --git a/SikRadio/Program.cs b/SikRadio/Program.cs index 826e388b06..7e681fccca 100644 --- a/SikRadio/Program.cs +++ b/SikRadio/Program.cs @@ -1,4 +1,4 @@ -using System; +using System; using System.Windows.Forms; using log4net; using log4net.Config; @@ -8,6 +8,26 @@ namespace SikRadio internal static class Program { private static readonly ILog log = LogManager.GetLogger("Program"); + private const string MANUFACTURER_PASSWORD = "--manufacturing"; + private const string ALLOW_DIFF_PROG = "--allowdiffprog"; + private static bool _Manufacturer = false; + private static bool _AllowDiffProg = false; + + public static bool Manufacturer + { + get + { + return _Manufacturer; + } + } + + public static bool AllowDiffProg + { + get + { + return _AllowDiffProg; + } + } /// /// The main entry point for the application. @@ -15,6 +35,18 @@ internal static class Program [STAThread] private static void Main(string[] args) { + foreach (var arg in args) + { + if (RFDLib.Text.Contains(arg, MANUFACTURER_PASSWORD)) + { + _Manufacturer = true; + } + if (RFDLib.Text.Contains(arg, ALLOW_DIFF_PROG)) + { + _AllowDiffProg = true; + } + } + log.Info("App Start"); XmlConfigurator.Configure(); diff --git a/SikRadio/Properties/AssemblyInfo.cs b/SikRadio/Properties/AssemblyInfo.cs index 84f9190bfa..133ed2071e 100644 --- a/SikRadio/Properties/AssemblyInfo.cs +++ b/SikRadio/Properties/AssemblyInfo.cs @@ -36,4 +36,4 @@ // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("0.0.*")] -[assembly: AssemblyFileVersion("0.0.0.0")] \ No newline at end of file +[assembly: AssemblyFileVersion("0.0.0.0")] diff --git a/SikRadio/Properties/Resources.Designer.cs b/SikRadio/Properties/Resources.Designer.cs index 127522ddce..ebf5a332ba 100644 --- a/SikRadio/Properties/Resources.Designer.cs +++ b/SikRadio/Properties/Resources.Designer.cs @@ -60,6 +60,16 @@ internal Resources() { } } + /// + /// Looks up a localized resource of type System.Byte[]. + /// + internal static byte[] RFDSiK_V3_00_rfd900x { + get { + object obj = ResourceManager.GetObject("RFDSiK_V3_00_rfd900x", resourceCulture); + return ((byte[])(obj)); + } + } + /// /// Looks up a localized resource of type System.Drawing.Bitmap. /// diff --git a/SikRadio/Properties/Resources.resx b/SikRadio/Properties/Resources.resx index 780715af2f..81432cbd0c 100644 --- a/SikRadio/Properties/Resources.resx +++ b/SikRadio/Properties/Resources.resx @@ -118,6 +118,9 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + ..\Resources\RFDSiK V3.00 rfd900x.bin;System.Byte[], mscorlib, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + ..\Resources\sik.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a diff --git a/SikRadio/RFD900.cs b/SikRadio/RFD900.cs index 14da57b4d5..18f82e16d1 100644 --- a/SikRadio/RFD900.cs +++ b/SikRadio/RFD900.cs @@ -2,6 +2,8 @@ using System.Collections.Generic; using System.Threading; using MissionPlanner.Radio; +using System.IO; +using System.Reflection; namespace RFD.RFD900 { @@ -13,11 +15,47 @@ public class TSession : IDisposable TMode _Mode = TMode.INIT; MissionPlanner.Comms.ICommsSerial _Port; public Uploader.Board Board = Uploader.Board.FAILED; + RFDLib.IO.ATCommand.TClient _ATCClient; + RFD900 _ModemObject; + int _MainFirmwareBaud; + /// + /// This is a work-around for radio firmware bugs in which not all settings + /// are described by an RTI5? command. + /// + Dictionary _DefaultSettings = new Dictionary(); + const int BOOTLOADERX_BAUD = 57600; const int BOOTLOADER_BAUD = 115200; + const string NODEID = "NODEID"; + const string NODEDESTINATION = "NODEDESTINATION"; - public TSession(MissionPlanner.Comms.ICommsSerial Port) + public TSession(MissionPlanner.Comms.ICommsSerial Port, int MainFirmwareBaud) { _Port = Port; + _ATCClient = new TATCClient(new TMissionPlannerSerialPort(Port)); + _ATCClient.Echoes = true; + _ATCClient.Terminator = "\r\n"; + _ATCClient.Timeout = 1000; + _MainFirmwareBaud = MainFirmwareBaud; + + // This is a work-around for radio firmware bugs in which not all settings + // are described by an RTI5? command. + AddDefaultSetting("S21:GPO1_3STATLED(N)[0..1]=0{Off,On,}\r\n"); + AddDefaultSetting("S22:GPO1_0TXEN485(N)[0..1]=0{Off,On,}\r\n"); + AddDefaultSetting("S23:RATE/FREQBAND(N)[0..3]=0{LoAus,HiAus,StdNZ,LoUSA,HiUSA,StdEU,LbtEU,StdPRC,StdINS,HiLbtJAP,HiStdJAP,LoLbtJAP,LoStdJAP,}\r\n"); + AddDefaultSetting("S20:ANT_MODE(N)[0..3]=0{Ant1&2,Ant1,Ant2,Ant1=TX;2=RX,}\r\n"); + } + + /// + /// Add a setting to the _DefaultSettings which is generated by parsing the given ATI5? query response line. + /// + /// The ATI5? query response line + void AddDefaultSetting(string ATI5QueryResponseLine) + { + var S = TSession.ParseATI5QueryResponseLine(ATI5QueryResponseLine); + if (S != null) + { + _DefaultSettings[S.Name] = S; + } } public enum TMode @@ -28,6 +66,11 @@ public enum TMode BOOTLOADER, //For a,u,+ BOOTLOADER_X, //For x UNKNOWN + } + + public void WriteToPort(string ToWrite) + { + _Port.Write(ToWrite); } public void Dispose() @@ -40,13 +83,13 @@ public bool WaitForToken(string Token, int MaxWait) return WaitForAnyOfTheseTokens(new string[] { Token }, MaxWait) >= 0; } - /// - /// Wait for any of these tokens to be received on the port. - /// Wait up to MaxWait milliseconds. If a token was received, return the array index of - /// the token. If no tokens received, return -1. - /// - /// The tokens to wait for. Must not be null. - /// The max wait time in milliseconds. + /// + /// Wait for any of these tokens to be received on the port. + /// Wait up to MaxWait milliseconds. If a token was received, return the array index of + /// the token. If no tokens received, return -1. + /// + /// The tokens to wait for. Must not be null. + /// The max wait time in milliseconds. /// The token array index of the token received, or -1 is none of the tokens received. public int WaitForAnyOfTheseTokens(string[] Tokens, int MaxWait) { @@ -58,20 +101,37 @@ public int WaitForAnyOfTheseTokens(string[] Tokens, int MaxWait) while (SW.ElapsedMilliseconds < MaxWait) { - string x = _Port.ReadExisting(); - Temp += x; - - for (int n = 0; n < Tokens.Length; n++) - { - if (Temp.Contains(Tokens[n])) - { - _Port.ReadTimeout = Timeout; - return n; + try + { + int Byte; + while (((Byte = _Port.ReadByte()) != -1) && (SW.ElapsedMilliseconds < MaxWait)) + { + //string x = _Port.ReadExisting(); + Temp += ((char)Byte); + + for (int n = 0; n < Tokens.Length; n++) + { + if (Temp.Contains(Tokens[n])) + { + _Port.ReadTimeout = Timeout; + return n; + } + } } + + Thread.Sleep(50); } + catch (Exception e) + { + //System.Diagnostics.Debug.WriteLine(e.Message); + //System.Diagnostics.Debug.WriteLine("No tokens, got " + Temp); - Thread.Sleep(50); + return -1; + } } + + //Console.WriteLine("Failed to get token, got this instead: " + Temp); + _Port.ReadTimeout = Timeout; return -1; } @@ -84,7 +144,6 @@ void WriteBootloaderCode(Uploader.Code Code) bool IsInBootloaderMode() { - int PrevBaud = _Port.BaudRate; _Port.BaudRate = BOOTLOADER_BAUD; Thread.Sleep(100); WriteBootloaderCode(Uploader.Code.EOC); @@ -103,7 +162,7 @@ bool IsInBootloaderMode() } if (!Result) { - _Port.BaudRate = PrevBaud; + _Port.BaudRate = _MainFirmwareBaud; } return Result; } @@ -114,6 +173,9 @@ bool IsInBootloaderMode() /// bool IsInBootloaderXMode() { + int PrevBaud = _Port.BaudRate; + _Port.BaudRate = BOOTLOADERX_BAUD; + //for (int n = 0; n < 3; n++) { Thread.Sleep(200); @@ -125,19 +187,16 @@ bool IsInBootloaderXMode() _Port.Write("CHIPID\r\n"); if (WaitForToken("RFD", 200)) { + //Leave baud rate at bootloader X baud rate. return true; } } + _Port.BaudRate = PrevBaud; return false; } - TMode DetermineMode() - { - if (IsInBootloaderXMode()) - { - return TMode.BOOTLOADER_X; - } - + bool TryEscapeFromTransparent() + { _Port.ReadTimeout = 2000; //Console.WriteLine("Waiting 1500ms"); Thread.Sleep(1500); @@ -145,10 +204,16 @@ TMode DetermineMode() //Console.WriteLine("Sending +++"); _Port.Write("+++"); //Console.WriteLine("Waiting up to 1.5s for OK"); - if (WaitForToken("OK\r\n", 1500)) + return WaitForToken("OK\r\n", 1500); + } + + TMode DetermineMode() + { + if (IsInBootloaderXMode()) { - return TMode.AT_COMMAND; + return TMode.BOOTLOADER_X; } + //Check if already in AT command mode. _Port.DiscardInBuffer(); _Port.Write("\r\n"); @@ -158,6 +223,12 @@ TMode DetermineMode() { return TMode.AT_COMMAND; } + + if (TryEscapeFromTransparent() || TryEscapeFromTransparent()) + { + return TMode.AT_COMMAND; + } + //Not in transparent or at command mode. Probably in bootloader mode. Need to verify. if (IsInBootloaderXMode()) { @@ -182,6 +253,14 @@ void CheckIfInBootloaderMode() } } + public RFDLib.IO.ATCommand.TClient ATCClient + { + get + { + return _ATCClient; + } + } + public MissionPlanner.Comms.ICommsSerial Port { get @@ -190,6 +269,79 @@ public MissionPlanner.Comms.ICommsSerial Port } } + /// + /// Get the modem object, assuming it can be put into AT command mode, or already is in AT command mode. + /// Returns null if could not get modem object. + /// + /// + public RFD900 GetModemObject() + { + if (_ModemObject == null) + { + switch (GetMode()) + { + case TMode.TRANSPARENT: + if (PutIntoATCommandMode() != TMode.AT_COMMAND) + { + return null; + } + goto case TMode.AT_COMMAND; + case TMode.AT_COMMAND: + string Result = _ATCClient.DoQuery("ATI2", true); + try + { + int Code = int.Parse(Result); + Uploader.Board Board = (Uploader.Board)Code; + switch (Board) + { + case Uploader.Board.DEVICE_ID_RFD900A: + _ModemObject = new RFD900a(this); + break; + case Uploader.Board.DEVICE_ID_RFD900P: + _ModemObject = new RFD900p(this); + break; + case Uploader.Board.DEVICE_ID_RFD900U: + _ModemObject = new RFD900u(this); + break; + case Uploader.Board.DEVICE_ID_RFD900UX: + _ModemObject = new RFD900ux(this); + break; + case Uploader.Board.DEVICE_ID_RFD900X: + _ModemObject = new RFD900x(this); + break; + case Uploader.Board.DEVICE_ID_RFD900X2: + _ModemObject = new RFD900X2(this); + break; + case Uploader.Board.DEVICE_ID_RFD900UX2: + _ModemObject = new RFD900UX2(this); + break; + } + } + catch + { + + } + + if (_ModemObject != null) + { + string ATIResponse = _ATCClient.DoQuery("ATI", true); + if (ATIResponse != null && ATIResponse.Contains("DINIO")) + { + _ModemObject.SetDINIO(); + } + } + break; + case TMode.BOOTLOADER: + _ModemObject = RFD900APU.GetObjectForModem(this); + break; + case TMode.BOOTLOADER_X: + _ModemObject = RFD900xux.GetObjectForModem(this); + break; + } + } + return _ModemObject; + } + public TMode GetMode() { if (_Mode == TMode.INIT) @@ -202,22 +354,22 @@ public TMode GetMode() public TMode PutIntoBootloaderMode() { var CurrentMode = GetMode(); - switch (CurrentMode) - { - case TMode.BOOTLOADER: - case TMode.BOOTLOADER_X: - break; - default: - CurrentMode = PutIntoATCommandMode(); - if (CurrentMode == TMode.AT_COMMAND) - { - _Port.Write("\r\n"); - Thread.Sleep(100); - _Port.Write("AT&UPDATE\r\n"); - Thread.Sleep(100); - CheckIfInBootloaderMode(); - } - break; + switch (CurrentMode) + { + case TMode.BOOTLOADER: + case TMode.BOOTLOADER_X: + break; + default: + CurrentMode = PutIntoATCommandMode(); + if (CurrentMode == TMode.AT_COMMAND) + { + _Port.Write("\r\n"); + Thread.Sleep(100); + _Port.Write("AT&UPDATE\r\n"); + Thread.Sleep(100); + CheckIfInBootloaderMode(); + } + break; } return GetMode(); @@ -231,10 +383,9 @@ public TMode PutIntoATCommandMode() case TMode.TRANSPARENT: return PutIntoATCommandModeAssumingInTransparentMode(); case TMode.BOOTLOADER: - int PrevBaud = _Port.BaudRate; _Port.BaudRate = BOOTLOADER_BAUD; WriteBootloaderCode(Uploader.Code.REBOOT); - _Port.BaudRate = PrevBaud; + _Port.BaudRate = _MainFirmwareBaud; _Mode = TMode.INIT; break; case TMode.BOOTLOADER_X: @@ -242,102 +393,130 @@ public TMode PutIntoATCommandMode() Thread.Sleep(100); _Port.Write("\r\n"); Thread.Sleep(100); - _Port.Write("BOOTNEW\r\n"); + _Port.Write("RESET\r\n"); Thread.Sleep(100); + _Port.BaudRate = _MainFirmwareBaud; _Mode = TMode.INIT; break; } return GetMode(); } - /// - /// Assuming in transparent mode, try to put it into AT command mode. - /// If fails, determine mode and then try again. + /// + /// Assuming in transparent mode, try to put it into AT command mode. + /// If fails, determine mode and then try again. /// - public TMode PutIntoATCommandModeAssumingInTransparentMode() - { + public TMode PutIntoATCommandModeAssumingInTransparentMode() + { _Port.ReadTimeout = 2000; //Console.WriteLine("Waiting 1500ms"); Thread.Sleep(1500); _Port.DiscardInBuffer(); //Console.WriteLine("Sending +++"); - _Port.Write("+++"); + _Port.Write("+++"); //Console.WriteLine("Waiting up to 3s for OK"); if (WaitForToken("OK\r\n", 3000)) { _Mode = TMode.AT_COMMAND; - return TMode.AT_COMMAND; - } - - _Mode = TMode.INIT; - return PutIntoATCommandMode(); + return TMode.AT_COMMAND; + } + + _Mode = TMode.INIT; + return PutIntoATCommandMode(); + } + + /// + /// Put into transparent mode. + /// + /// + public TMode PutIntoTransparentMode() + { + if (GetMode() == TMode.TRANSPARENT) + { + System.Diagnostics.Debug.WriteLine("Already in transparent mode"); + return TMode.TRANSPARENT; + } + else + { + if (PutIntoATCommandMode() == TMode.AT_COMMAND) + { + _Port.Write("\r\n"); + Thread.Sleep(100); + _Port.Write("ATO\r\n"); + Thread.Sleep(100); + if (WaitForToken("ATO\r\n", 100)) + { + System.Diagnostics.Debug.WriteLine("Put into transparent mode OK"); + } + else + { + System.Diagnostics.Debug.WriteLine("Failed to put into transparent mode"); + } + _Mode = TMode.TRANSPARENT; + return TMode.TRANSPARENT; + } + else + { + System.Diagnostics.Debug.WriteLine("Failed to put into AT cmd mode"); + return TMode.UNKNOWN; + } + } + } + + public void AssumeMode(TMode Mode) + { + if (Mode == TMode.BOOTLOADER_X) + { + _Port.BaudRate = BOOTLOADERX_BAUD; + } + else + { + _Port.BaudRate = _MainFirmwareBaud; + } + _Mode = Mode; } /// - /// Put into transparent mode. + /// Skip over the multipoint node number in an ATI5 or ATI5? response line. /// - /// - public TMode PutIntoTransparentMode() + /// The response line + /// The character index of the designator. + static int SkipMultipointNodeNumber(string Line) { - if (GetMode() == TMode.TRANSPARENT) - { - System.Diagnostics.Debug.WriteLine("Already in transparent mode"); - return TMode.TRANSPARENT; - } - else + int n = 0; + + for (; n < Line.Length; n++) { - if (PutIntoATCommandMode() == TMode.AT_COMMAND) - { - _Port.Write("\r\n"); - Thread.Sleep(100); - _Port.Write("ATO\r\n"); - Thread.Sleep(100); - if (WaitForToken("ATO\r\n", 100)) - { - System.Diagnostics.Debug.WriteLine("Put into transparent mode OK"); - } - else - { - System.Diagnostics.Debug.WriteLine("Failed to put into transparent mode"); - } - _Mode = TMode.TRANSPARENT; - return TMode.TRANSPARENT; - } - else + if (RFDLib.Text.CheckIsLetter(Line[n])) { - System.Diagnostics.Debug.WriteLine("Failed to put into AT cmd mode"); - return TMode.UNKNOWN; + return n; } } - } - - public void AssumeMode(TMode Mode) - { - _Mode = Mode; - } + return 0; + } + /// /// Parse the setting designator from the given Line and character positon. /// /// The ATI5? line. Must not be null. /// The current character position. /// - string ParseDesignator(string Line, ref int n) + static string ParseDesignator(string Line, ref int n) { - n = 0; + n = SkipMultipointNodeNumber(Line); string Designator = ""; - - if (RFDLib.Text.CheckIsLetter(Line[0])) + + if (RFDLib.Text.CheckIsLetter(Line[n])) { - Designator += Line[0]; + Designator += Line[n]; + n++; } else { return null; } - n = 1; - while (Line[n] != ':') { if (RFDLib.Text.CheckIsNumeral(Line[n])) @@ -354,7 +533,7 @@ string ParseDesignator(string Line, ref int n) return Designator; } - string ParseName(string Line, ref int n) + static string ParseName(string Line, ref int n) { string Name = ""; while (true) @@ -371,7 +550,7 @@ string ParseName(string Line, ref int n) } } - bool ParseType(string Line, ref int n) + static bool ParseType(string Line, ref int n) { for (; Line[n] != ')'; n++) { @@ -380,34 +559,60 @@ bool ParseType(string Line, ref int n) return true; } - bool ParseIntUntil(string Line, ref int n, string Delimiter, out int Value) + /// + /// Parse an integer from the given string, starting at the given character index until a delimiter + /// is reached. + /// + /// The string to parse from. Must not be null. + /// The start character index, to be updated to be at the end of the value + /// and/or delimiter. + /// The delimiter to end at. Can be null if not applicable. + /// The value parsed. + /// true if parsed, otherwise false. + static bool ParseIntUntil(string Line, ref int n, string Delimiter, out int Value) { string Temp = ""; + //Copy all the characters which are decimal numerals to Temp, incrementing + //n until it is at a non-numeral character. while ((n < Line.Length) && RFDLib.Text.CheckIsNumeral(Line[n])) { Temp += Line[n]; n++; } + //Parse Temp. Value = int.Parse(Temp); + //If no delimiter specified... if (Delimiter == null) { + //Just return now. return true; } else { + //If the delimiter exists in the string and it's at the current character index... if (Line.IndexOf(Delimiter, n) == n) { + //Move the character index to character after the end of it. n += Delimiter.Length; return true; } else { + //The delimiter doesn't exist. Return that failed. return false; } } } - TSetting.TRange ParseRange(string Line, ref int n) + /// + /// Parse a [min..max] range + /// + /// The ATI5? response line to parse from. Must not be null. + /// The index of the character to start parsing from. This is also updated to be + /// just after the end of the range. + /// The parameter name. Must not be null. + /// The range if successfully parsed, otherwise null. + static TSetting.TRange ParseRange(string Line, ref int n, string Name) { if (Line[n] != '[') { @@ -424,15 +629,15 @@ TSetting.TRange ParseRange(string Line, ref int n) { return null; } - return new TSetting.TRange(Min, Max); + return new TSetting.TSimpleRange(Min, Max, GetIncrement(Name)); } - bool ParseValue(string Line, ref int n, out int Value) + static bool ParseValue(string Line, ref int n, out int Value) { return ParseIntUntil(Line, ref n, null, out Value); } - bool CharArrayContains(char[] Array, char x) + static bool CharArrayContains(char[] Array, char x) { foreach (var c in Array) { @@ -444,7 +649,7 @@ bool CharArrayContains(char[] Array, char x) return false; } - string GetStringUntil(string Line, ref int n, char[] Tokens) + static string GetStringUntil(string Line, ref int n, char[] Tokens) { string Result = ""; while (!CharArrayContains(Tokens, Line[n])) @@ -455,7 +660,7 @@ string GetStringUntil(string Line, ref int n, char[] Tokens) return Result; } - string[] ParseOptions(string Line, ref int n) + static string[] ParseOptions(string Line, ref int n) { if (Line[n] != '{') { @@ -483,7 +688,13 @@ string[] ParseOptions(string Line, ref int n) return Options.ToArray(); } - int[] CheckIfAllIntegers(string[] Options) + /// + /// Try to parse every element in the given array of strings to integers. + /// If successful, return the corresponding array of integers, otherwise return null. + /// + /// The array of strings to convert. Must not be null. + /// The array of integers, or null if unsuccessful. + static int[] CheckIfAllIntegers(string[] Options) { int[] Result = new int[Options.Length]; @@ -497,18 +708,84 @@ int[] CheckIfAllIntegers(string[] Options) return Result; } - float GetScaleFactor(string Name) + static float GetScaleFactor(string Name, int[] Ints, int Value) { switch (Name) { case "SERIAL_SPEED": + foreach (var i in Ints) + { + if (i < 1000) + { + return 1; + } + } return 0.001F; + default: + if (Value != 0) + { + //Check if value matches one of the options divided by 1000. + foreach (var i in Ints) + { + if (i == Value) + { + return 1; + } + } + foreach (var i in Ints) + { + if ((i / 1000) == Value) + { + return 0.001F; + } + } + } + break; } return 1; } - TSetting.TOption[] CreateOptions(TSetting.TRange Range, string[] Options, - string Name) + static bool IsCapitalLetter(char Letter) + { + return (Letter >= 'A') && (Letter <= 'Z'); + } + + /* + * A new word starts when it goes from a lower case to upper case, + * or the character before the transition from upper case to lower. + */ + static string[] SplitOptionName(string OptionName) + { + int LastStart = 0; + List Result = new List(); + + for (int n = 1; n < OptionName.Length; n++) + { + if (IsCapitalLetter(OptionName[n]) && !IsCapitalLetter(OptionName[n-1])) + { + Result.Add(OptionName.Substring(LastStart, n - LastStart)); + LastStart = n; + } + else if (IsCapitalLetter(OptionName[n-1]) && !IsCapitalLetter(OptionName[n])) + { + if (LastStart != (n-1)) + { + Result.Add(OptionName.Substring(LastStart, n - LastStart-1)); + LastStart = n-1; + } + } + } + + if (LastStart < OptionName.Length) + { + Result.Add(OptionName.Substring(LastStart, OptionName.Length - LastStart)); + } + + return Result.ToArray(); + } + + static TSetting.TOption[] CreateOptions(TSetting.TRange Range, string[] Options, + string Name, int Value) { if (Range == null || Options == null) { @@ -516,10 +793,11 @@ TSetting.TOption[] CreateOptions(TSetting.TRange Range, string[] Options, } int[] Ints = CheckIfAllIntegers(Options); + //If all of the strings were integers... if (Ints != null) { TSetting.TOption[] Result = new TSetting.TOption[Ints.Length]; - float SF = GetScaleFactor(Name); + float SF = GetScaleFactor(Name, Ints, Value); for (int n = 0; n < Result.Length; n++) { Result[n] = new TSetting.TOption((int)(SF * Ints[n]), Options[n]); @@ -527,26 +805,95 @@ TSetting.TOption[] CreateOptions(TSetting.TRange Range, string[] Options, return Result; } - //Not all integers. - if (Range == null) - { - return null; - } + int[] RO = Range.GetOptionsIncludingValue(Value); if (Options.Length == 2) { //Match up with min and max. TSetting.TOption[] Result = new TSetting.TOption[2]; - Result[0] = new TSetting.TOption(Range.Min, Options[0]); - Result[1] = new TSetting.TOption(Range.Max, Options[1]); + + Result[0] = new TSetting.TOption(RO[0], Options[0]); + Result[1] = new TSetting.TOption(RO[RO.Length-1], Options[1]); return Result; } + else if (RO.Length == Options.Length) + { + TSetting.TOption[] Result = new TSetting.TOption[RO.Length]; + for (int n = 0; n < (RO.Length); n++) + { + Result[n] = new TSetting.TOption(RO[n], Options[n]); + } + return Result; + } + else if (RO.Length < Options.Length) + { + //Account for the freq/band setting. + string[] ResultOptionStrings = new string[RO.Length]; + string CountryCode = null; + int OptionIndex = 0; + bool GotToMax = false; + + //For each option... + foreach (var O in Options) + { + string[] Temp = SplitOptionName(O); + if (Temp.Length != 0) + { + //Extract country code from option name + string CCTemp = Temp[Temp.Length - 1]; + //If we're still on the same contry code... + if (CCTemp == CountryCode) + { + OptionIndex++; + if (OptionIndex >= (ResultOptionStrings.Length - 1)) + { + GotToMax = true; + } + } + else + { + OptionIndex = 0; + CountryCode = CCTemp; + } + + if (OptionIndex < ResultOptionStrings.Length) + { + if (ResultOptionStrings[OptionIndex] == null) + { + ResultOptionStrings[OptionIndex] = ""; + } + if (OptionIndex < ResultOptionStrings.Length) + { + if (ResultOptionStrings[OptionIndex].Length != 0) + { + ResultOptionStrings[OptionIndex] += "/"; + } + ResultOptionStrings[OptionIndex] += O; + } + } + } + } + + if (GotToMax) + { + TSetting.TOption[] Result = new TSetting.TOption[RO.Length]; + for (int n = 0; n < RO.Length; n++) + { + Result[n] = new TSetting.TOption(RO[n], ResultOptionStrings[n]); + } + return Result; + } + else + { + return null; + } + } else { return null; } } - int GetIncrement(string Name) + static int GetIncrement(string Name) { switch (Name) { @@ -569,7 +916,7 @@ int GetIncrement(string Name) /// /// The line. Must not be null. /// The setting parsed, or null if could not parse setting. - TSetting ParseATI5QueryResponseLine(string Line) + public static TSetting ParseATI5QueryResponseLine(string Line) { try { @@ -585,7 +932,9 @@ TSetting ParseATI5QueryResponseLine(string Line) n++; string Name = ParseName(Line, ref n); - if (Name == null || Name.Length == 0) + + //Ignore "reserved" setting (it's not a setting, just a reserved place for a setting). + if (Name == null || Name.Length == 0 || Name == "RESERVED") { return null; } @@ -596,7 +945,7 @@ TSetting ParseATI5QueryResponseLine(string Line) { return null; } - Range = ParseRange(Line, ref n); + Range = ParseRange(Line, ref n, Name); if (Range == null) { return null; @@ -631,7 +980,7 @@ TSetting ParseATI5QueryResponseLine(string Line) } return new TSetting(Designator, Name, Range, Value, - CreateOptions(Range, Options, Name), GetIncrement(Name)); + CreateOptions(Range, Options, Name, Value), GetIncrement(Name)); } catch { @@ -639,6 +988,47 @@ TSetting ParseATI5QueryResponseLine(string Line) } } + /// + /// Parse an ATI5 response line to a TShortSetting. + /// + /// + /// + TShortSetting ParseATI5ResponseLine(string Line) + { + try + { + int n = 0; + string Designator = ParseDesignator(Line, ref n); + if (Designator == null) + { + return null; + } + + n++; + string Name = ParseName(Line, ref n); + if (Name == null || Name.Length == 0) + { + return null; + } + if (Line[n] != '=') + { + return null; + } + n++; + + int Value; + if (!ParseValue(Line, ref n, out Value)) + { + return null; + } + return new TShortSetting(Designator, Name, Value); + } + catch + { + return null; + } + } + TSetting.TOption[] GetBaudRateOptionsGivenRawBaudRates(int[] Rates) { List Options = new List(); @@ -668,8 +1058,8 @@ TSetting.TOption[] GetDefaultBaudRateSettingForBoard(Uploader.Board Board) /// /// The full ATI5 query response. Must not be null. /// A dictionary of settings found, with name as key. Never null. - Dictionary ParseATI5QueryResponse(string ATI5Response, - Dictionary Dict) + Dictionary ParseATI5QueryResponse(string ATI5Response, + Dictionary Dict) { foreach (var Line in ATI5Response.Split('\n', '\r')) { @@ -683,32 +1073,456 @@ Dictionary ParseATI5QueryResponse(string ATI5Response, return Dict; } - public Dictionary GetSettings(string ATI5Response, - Uploader.Board Board) + Dictionary ParseATI5Response(string ATI5Response, + Dictionary Dict) { - Dictionary Result = new Dictionary(); - ParseATI5QueryResponse(ATI5Response, Result); - string SerialName = "SERIAL_SPEED"; - if (Result.ContainsKey(SerialName)) + foreach (var Line in ATI5Response.Split('\n', '\r')) { - if (Result[SerialName].Options == null) + var S = ParseATI5ResponseLine(Line); + if (S != null) { - Result[SerialName].Options = GetDefaultBaudRateSettingForBoard(Board); + Dict[S.Name] = S; } } - return Result; + + return Dict; } - } - public class TSetting - { + TTextSetting GetEncryptionKey(bool Remote) + { + string Temp = _ATCClient.DoQuery((Remote ? "R" : "A") + "T&E?", true); + + if (!Temp.Contains("OK") && !Temp.Contains("ERROR")) + { + foreach (char c in Temp) + { + if (!RFDLib.Text.CheckIsHexNumeral(c)) + { + return null; + } + } + + var Result = new TTextSetting(); + Result.Designator = "&E"; + Result.Name = ENC_KEY_SETTING_NAME; + Result.Text = Temp; + + return Result; + } + + return null; + } + + /// + /// Parse the ATI5? and ATI5 responses to get a set of settings objects. Settings are only returned if they're + /// in the ATI5QResponse, or Ranges. + /// + /// The ATI5? response + /// The board + /// The ATI5 response + /// A previous set of settings received to use the ranges from, in the + /// case that they can't be ascertained from ATI5QResponse. Can be null if not specified. + /// Never null + public Dictionary GetSettings(string ATI5QResponse, + Uploader.Board Board, string ATI5Response, + Dictionary Ranges, out bool UseRanges) + { + UseRanges = false; + + Dictionary Result = new Dictionary(); + ParseATI5QueryResponse(ATI5QResponse, Result); + + if (Result.Count == 0) + { + UseRanges = true; + } + else + { + string SerialName = "SERIAL_SPEED"; + if (Result.ContainsKey(SerialName) && Result[SerialName] is TSetting) + { + if (((TSetting)Result[SerialName]).Options == null) + { + ((TSetting)Result[SerialName]).Options = GetDefaultBaudRateSettingForBoard(Board); + } + } + } + + //The code below is all done to work-around the case of SiK RFD900x 3.07 bug in + //which are RTI5? commands response is cut-off for settings S21 through S23. + Dictionary ShortSettings = new Dictionary(); + ParseATI5Response(ATI5Response, ShortSettings); + + if (UseRanges && (Ranges != null)) + { + Result = CopySettingsButUseDifferentRanges(ShortSettings, Ranges); + } + + foreach (var kvp in _DefaultSettings) + { + if (ShortSettings.ContainsKey(kvp.Key) && !Result.ContainsKey(kvp.Key)) + { + kvp.Value.Value = ShortSettings[kvp.Key].Value; + Result[kvp.Key] = kvp.Value; + } + } + + //If the result contains a nodeid and nodedestination parameter, it's multipoint firmware + //and it needs its settings ranges modified... + //We want the node dest to have the same options as node id, except we want the + //last value parsed for node dest to be appended to the end for the node dest. + if (Result.ContainsKey(NODEID) && Result.ContainsKey(NODEDESTINATION) && + Result[NODEID] is TSetting && Result[NODEDESTINATION] is TSetting) + { + var NodeIDRange = ((TSetting)Result[NODEID]).Range; + var NodeDestRange = ((TSetting)Result[NODEDESTINATION]).Range; + //If the destination id range is null... + if (NodeDestRange == null) + { + //Do nothing + } + else if (NodeIDRange != null) + { + //Both parameters have parsed ranges... + if (NodeIDRange is TSetting.TSimpleRange) + { + //The node id range is a simple range. + var NodeIDOptions = NodeIDRange.GetOptionsIncludingValue(((TSetting)Result[NODEID]).Value); + var NodeDestOptions = NodeDestRange.GetOptionsIncludingValue(((TSetting)Result[NODEDESTINATION]).Value); + if (NodeDestOptions[NodeDestOptions.Length-1] > NodeIDOptions[NodeIDOptions.Length-1]) + { + ((TSetting)Result[NODEDESTINATION]).Range = new TSetting.TMultiRange(new TSetting.TSimpleRange[] + { + (TSetting.TSimpleRange)NodeIDRange, + new TSetting.TSimpleRange(NodeDestOptions[NodeDestOptions.Length-1], NodeDestOptions[NodeDestOptions.Length-1], 1) + } + ); + } + } + } + } + + return Result; + } + + /// + /// Copy the given dictionary of Values, but use the specified valid ranges/options + /// in the given Settings dictionary if they exist in there. + /// + /// This is useful for the case + /// of a local modem returning a full "ATI5?" reply, but the remote modem only returning + /// an "RTI5" reply. In this case, the values returned from RTI5 can be used, but the + /// ATI5? reply is used to assume the valid ranges of the settings of the remote modem. + /// + /// The values to use in the result. + /// The ranges/options to use in the result. + /// The resulting settings which contains the same values as Values, but has ranges/options + /// as specified in Settings (if they exist in there) + public Dictionary CopySettingsButUseDifferentRanges( + Dictionary Values, + Dictionary Settings) + { + Dictionary Result = new Dictionary(); + + foreach (var kvp in Values) + { + if (Settings.ContainsKey(kvp.Key) && Settings[kvp.Key] is TSetting) + { + var S = (TSetting)Settings[kvp.Key].Clone(); + S.Value = kvp.Value.Value; + Result[kvp.Key] = S; + } + } + + return Result; + } + + /// + /// Use the newer ATI10 command to assemble the same format string as the old ATI5? command. + /// ATI5? command has been deprecated, and ATI10 is used in its place. Returns the complete string, + /// or null if unsuccessful. + /// + /// The complete string, or null if unsuccessful. + public string UseATI10ToGetATI5QueryResponse(bool Remote) + { + int ParamIndex; + string Result = ""; + string Prefix = Remote ? "RTI10:" : "ATI10:"; + + for (ParamIndex = 0; ; ParamIndex++) + { + string Line = ATCClient.DoQuery(Prefix + ParamIndex.ToString(), true); + if (RFDLib.Text.Contains(Line, "error") || (Line.Length == 0)) + { + return null; + } + else if (RFDLib.Text.Contains(Line, "eof") || !Line.Contains("=")) + { + return Result; + } + else + { + Result += Line + "\r\n"; + } + } + } + + /// + /// Query the remote modem for its settings valid ranges and parse the given RTI5 response to get a set of settings objects. + /// + /// The board + /// The RTI5 response + /// A previous set of settings received to use the ranges from, in the + /// case that they can't be ascertained from querying the modem. Can be null if not specified. + /// Never null + public Dictionary GetSettings(bool Remote, Uploader.Board Board, string ATI5Response, + Dictionary Ranges, out bool UseRanges) + { + string ATI5QR = UseATI10ToGetATI5QueryResponse(Remote); + if (ATI5QR == null || (ATI5QR.Length == 0)) + { + ATI5QR = ATCClient.DoQueryWithMultiLineResponse(Remote ? "RTI5?" : "ATI5?"); + } + + var Result = GetSettings(ATI5QR, Board, ATI5Response, Ranges, out UseRanges); + + var EncKey = GetEncryptionKey(Remote); + + if (EncKey != null) + { + Result[ENC_KEY_SETTING_NAME] = EncKey; + } + + return Result; + } + + const string ENC_KEY_SETTING_NAME = "AESKEY"; + } + + public class TSettings + { + Dictionary _Settings = new Dictionary(); + const string MIN_FREQ = "MIN_FREQ"; + const string MAX_FREQ = "MAX_FREQ"; + + public TSettings(Dictionary Settings) + { + _Settings = Settings; + } + + public Dictionary Settings + { + get + { + return _Settings; + } + } + + public TSettings Clone() + { + Dictionary Temp = new Dictionary(); + + foreach (var kvp in _Settings) + { + Temp[kvp.Key] = (TBaseSetting)kvp.Value.Clone(); + } + + return new TSettings(Temp); + } + + public bool SaveToFile(string Path) + { + try + { + using (StreamWriter Writer = File.CreateText(Path)) + { + //Save in alphabetical order... + List Names = new List(_Settings.Keys); + Names.Sort(); + + foreach (var N in Names) + { + Writer.WriteLine(N + " = " + _Settings[N].GetValueAsString()); + } + } + + return true; + } + catch + { + return false; + } + } + + TNameAndValue ParseINILine(string Line) + { + if (!Line.Trim().StartsWith(";") && !Line.Trim().StartsWith("#")) + { + string[] ContentAndComment = Line.Split(';', '#'); + + if (ContentAndComment.Length >= 1) + { + string Content = ContentAndComment[0]; + + if (Content.Contains("=")) + { + string[] NameAndValue = Content.Split('='); + + if (NameAndValue.Length == 2) + { + string Name = NameAndValue[0].Trim(); + + return new TNameAndValue(Name, NameAndValue[1].Trim()); + } + } + } + } + + return null; + } + + /// + /// Update these settings from a file. + /// + /// The path of the settings file. Must not be null. + /// The names and values loaded. Null if failed. + public Dictionary LoadFromFile(string Path) + { + Dictionary Result = new Dictionary(); + + try + { + using (StreamReader Reader = File.OpenText(Path)) + { + string Line; + + while ((Line = Reader.ReadLine()) != null) + { + var NV = ParseINILine(Line); + if (NV != null && _Settings.ContainsKey(NV.Name)) + { + _Settings[NV.Name].SetValueFromString(NV.Value); + Result[NV.Name] = NV; + } + } + } + + return Result; + } + catch + { + return null; + } + } + + /// + /// Check if this set of settings is valid. Return a list of error descriptions. + /// If returned array is zero-length, settings are valid. + /// + /// + public string[] CheckValid() + { + List Result = new List(); + + if (_Settings.ContainsKey(MIN_FREQ) && _Settings.ContainsKey(MAX_FREQ)) + { + var Min = _Settings[MIN_FREQ]; + var Max = _Settings[MAX_FREQ]; + + if (Min is TShortSetting && Max is TShortSetting) + { + if (((TShortSetting)Min).Value > ((TShortSetting)Max).Value) + { + Result.Add("MIN_FREQ can't be more than MAX_FREQ"); + } + } + } + + return Result.ToArray(); + } + + public class TNameAndValue + { + public readonly string Name; + public readonly string Value; + + public TNameAndValue(string Name, string Value) + { + this.Name = Name; + this.Value = Value; + } + } + } + + public abstract class TBaseSetting : ICloneable + { public string Designator; public string Name; + + public abstract string GetValueAsString(); + public abstract void SetValueFromString(string Text); + public abstract object Clone(); + } + + public class TTextSetting : TBaseSetting + { + public string Text; + + public override string GetValueAsString() + { + return Text; + } + + public override void SetValueFromString(string Text) + { + this.Text = Text; + } + + public override object Clone() + { + TTextSetting Result = new TTextSetting(); + Result.Designator = Designator; + Result.Name = Name; + Result.Text = Text; + + return Result; + } + } + + + public class TShortSetting : TBaseSetting + { + public int Value; + + public TShortSetting(string Designator, string Name, int Value) + { + this.Designator = Designator; + this.Name = Name; + this.Value = Value; + } + + public override object Clone() + { + return new TShortSetting(Designator, Name, Value); + } + + public override string GetValueAsString() + { + return Value.ToString(); + } + + public override void SetValueFromString(string Text) + { + int.TryParse(Text, out this.Value); + } + } + + public class TSetting : TShortSetting + { /// /// null if range unknown /// public TRange Range; - public int Value; /// /// null if options unknown /// @@ -717,6 +1531,7 @@ public class TSetting public TSetting(string Designator, string Name, TRange Range, int Value, TOption[] Options, int Increment) + : base(Designator, Name, Value) { this.Designator = Designator; this.Name = Name; @@ -726,279 +1541,991 @@ public TSetting(string Designator, string Name, TRange Range, int Value, TOption this.Increment = Increment; } - public string[] GetOptionNames() + public override object Clone() + { + return new TSetting(Designator, Name, Range, Value, Options, Increment); + } + + public string[] GetOptionNames() + { + if (Options == null) + { + return null; + } + else + { + return RFDLib.Array.CherryPickArray(Options, (x) => x.OptionName); + } + } + + public string GetOptionNameForValue(string Value) + { + if (Options != null) + { + foreach (var O in Options) + { + if (O.Value.ToString() == Value) + { + return O.OptionName; + } + } + } + return null; + } + + /// + /// Returns whether this setting is a flag/boolean. + /// + /// + public bool GetIsFlag() + { + return (Range != null) && Range.GetOptions().Length == 2 && + Range.GetOptions()[0] == 0 && Range.GetOptions()[1] == 1; + } + + public abstract class TRange + { + public abstract int[] GetOptions(); + + /// + /// Get the list of options and include the option with the given value if it doesnt exist. + /// + /// The value to include. + /// The options. Never null. + public int[] GetOptionsIncludingValue(int Value) + { + List Result = new List(); + bool GotValue = false; + + foreach (var n in GetOptions()) + { + if (n == Value) + { + GotValue = true; + } + if (!GotValue) + { + if (n > Value) + { + Result.Add(Value); + GotValue = true; + } + } + + Result.Add(n); + } + + if (!GotValue) + { + Result.Add(Value); + } + + return Result.ToArray(); + } + } + + public class TSimpleRange : TRange + { + public readonly int Min; + public readonly int Max; + public readonly int Increment; + + public TSimpleRange(int Min, int Max, int Increment) + { + this.Min = Min; + this.Max = Max; + this.Increment = Increment; + } + + public override int[] GetOptions() + { + int[] list; + int index = 0; + bool GotEnd = false; + + int Min = this.Min; + int Max = this.Max; + + //Prevent exception for the case of the modem firmware erroneously specifiying a range in which max is less than min. + if (Max < Min) + { + Max = Min; + } + + if (Min == Max) + { + list = new int[1]; + } + else + { + list = new int[((Max - Min - 1) / Increment) + 2]; + } + + for (var a = Min; a <= Max; a += Increment) + { + if (a == Max) + { + GotEnd = true; + } + list[index++] = a; + } + + if (!GotEnd) + { + list[index++] = Max; + } + + return list; + } + } + + public class TMultiRange : TRange + { + TSimpleRange[] _SimpleRanges; + + public TMultiRange(TSimpleRange[] SimpleRanges) + { + _SimpleRanges = SimpleRanges; + } + + public override int[] GetOptions() + { + int TotalLength = 0; + int SRIndex; + + for (SRIndex = 0; SRIndex < _SimpleRanges.Length; SRIndex++) + { + TotalLength += _SimpleRanges[SRIndex].GetOptions().Length; + } + + int[] Result = new int[TotalLength]; + int ResultIndex = 0; + + for (SRIndex = 0; SRIndex < _SimpleRanges.Length; SRIndex++) + { + int[] SubResult = _SimpleRanges[SRIndex].GetOptions(); + Array.Copy(SubResult, 0, Result, ResultIndex, SubResult.Length); + ResultIndex += SubResult.Length; + } + + return Result; + } + } + + public class TOption + { + public readonly int Value; + public readonly string OptionName; + + public TOption(int Value, string OptionName) + { + this.Value = Value; + this.OptionName = OptionName; + } + } + } + + public abstract class RFD900 + { + protected TSession _Session; + bool _IsDINIO = false; + + public RFD900(TSession Session) + { + _Session = Session; + } + + /// + /// Returns whether the firmware model is allowed to be different to the connected modem model. + /// + /// + bool FirmwareDiffExempt() + { + return false; + } + + bool CheckFirmwareIncludingFileNameOK(string FilePath) + { + try + { + return (!IsDINIO || System.IO.Path.GetFileName(FilePath).Contains("DINIO")) && CheckFirmwareOK(FilePath); + } + catch + { + return CheckFirmwareOK(FilePath); + } + } + + public Uploader.Frequency GetBand() + { + try + { + var FreqString = _Session.ATCClient.DoQuery("ATI3", true); + if (FreqString.Contains("]")) + { + FreqString = FreqString.Split(']')[1]; + } + + System.Globalization.NumberStyles style = System.Globalization.NumberStyles.Any; + + if (FreqString.ToLower().Contains("x")) + { + style = System.Globalization.NumberStyles.AllowHexSpecifier; + } + + var freq = + (Uploader.Frequency) + Enum.Parse(typeof(Uploader.Frequency), + int.Parse(FreqString.ToLower().Replace("x", ""), style).ToString()); + + return freq; + } + catch + { + return Uploader.Frequency.FREQ_NONE; + } + } + + /// + /// Program firmware into modem, firstly doing necessary checks. + /// + /// The path of the firmware. Must not be null. + /// A callback to report progress. + /// true if succeeded, false if failed. + public virtual bool ProgramFirmware(string FilePath, Action Progress) + { + if (CheckFirmwareIncludingFileNameOK(FilePath) || FirmwareDiffExempt()) + { + Progress("Putting into bootloader mode.", double.NaN); + var Mode = _Session.PutIntoBootloaderMode(); + switch (Mode) + { + case TSession.TMode.BOOTLOADER: + case TSession.TMode.BOOTLOADER_X: + Progress("Programming selected firmware into modem.", double.NaN); + return DoFirmwareProgramming(FilePath, Progress); + default: + Progress("Failed to put into bootloader mode.", double.NaN); + return false; + } + } + else + { + Progress("Incorrect firmware selected.", double.NaN); + System.Threading.Thread.Sleep(2000); + return false; + } + } + + /// + /// The function which actually programs the firmware, doesn't check the firmware first, etc. + /// + /// The firmware file path. Must not be null. + /// The programming progress callback. Must not be null. + /// true if successful, false if failed. + protected abstract bool DoFirmwareProgramming(string FilePath, Action Progress); + protected abstract bool CheckFirmwareOK(string FilePath); + + static bool SearchTokenUpdate(byte[] Token, ref int TokenIndex, byte NextByte) + { + if (NextByte == Token[TokenIndex]) + { + if (++TokenIndex >= Token.Length) + { + //Found it. + return true; + } + } + else + { + TokenIndex = 0; + } + return false; + } + + /// + /// Search the given binary file for the given tokens + /// + /// The binary file path. Must not be null. + /// The tokens. Must not be null. + /// true if at least one token found, false if not. + protected static bool SearchBinary(string BinFilePath, string[] Tokens) + { + foreach (var Token in Tokens) + { + byte[] BinToken = System.Text.ASCIIEncoding.ASCII.GetBytes(Token); + + using (System.IO.FileStream FS = new System.IO.FileStream(BinFilePath, System.IO.FileMode.Open)) + { + int Byte; + int TokenIndex = 0; + while ((Byte = FS.ReadByte()) != -1) + { + if (SearchTokenUpdate(BinToken, ref TokenIndex, (byte)Byte)) + { + return true; + } + } + } + } + + return false; + } + + /// + /// Search the given hex file for the given tokens. + /// + /// The file to search. Must not be null. + /// The tokens to search for. Must not be null. + /// true if at least one found, false if not found. + protected static bool SearchHex(IHex File, string[] Tokens) + { + foreach (var Token in Tokens) + { + int TokenIndex = 0; + byte[] BinToken = System.Text.ASCIIEncoding.ASCII.GetBytes(Token); + + foreach (var Part in File.Values) + { + foreach (byte b in Part) + { + if (SearchTokenUpdate(BinToken, ref TokenIndex, b)) + { + return true; + } + } + } + } + return false; + } + + protected abstract string[] GetFirmwareSearchTokens(); + + protected void ShowWrongFirmwareMessageBox() + { + { + string S = "File doesn't appear to be valid for this radio. Could not find "; + var Tokens = GetFirmwareSearchTokens(); + for (int n = 0; n < Tokens.Length; n++) + { + if (n != 0) + { + if (n >= (Tokens.Length - 1)) + { + S += " or "; + } + else + { + S += ", "; + } + } + S += "\"" + Tokens[n] + "\""; + } + + S += " in File."; + + System.Windows.Forms.MessageBox.Show(S); + } + } + + public abstract Uploader.Board Board { get; } + + public bool IsDINIO + { + get + { + return _IsDINIO; + } + } + + public abstract string[] FirmwareFileNameExtensions { get; } + + public void SetDINIO() + { + _IsDINIO = true; + } + + /// + /// Tries to extract the firmware version string from the ATI command response. + /// + /// ATI(/RTI) command response. Must not be null. + /// The version string, if found, otherwise null. + public static string ATIResponseToFWVersion(string ATIResponse) + { + if (ATIResponse.Contains("RFD") && ATIResponse.Contains("on")) + { + int RFD = ATIResponse.IndexOf("RFD"); + int on = ATIResponse.IndexOf("on"); + + if (on > RFD) + { + return ATIResponse.Substring(RFD + 3, on - RFD - 3).Trim(); + } + } + + return null; + } + } + + public abstract class RFD900APU : RFD900 + { + public RFD900APU(TSession Session) + : base(Session) + { + + } + + /// + /// Check whether the firmware in the given path is suitable for this modem. + /// + /// The path to the firmware. Must not be null. + /// true if OK, false if not. + protected override bool CheckFirmwareOK(string FilePath) + { + try + { + IHex Hex = new IHex(); + Hex.load(FilePath); + + if (SearchHex(Hex, GetFirmwareSearchTokens())) + { + return true; + } + else + { + ShowWrongFirmwareMessageBox(); + return false; + } + } + catch + { + return false; + } + } + + /// + /// Do the firmware programming without doing any checks. + /// + /// The path of the firmware file to program. Must not be null. + /// A callback for progress. + /// true if succeeded, false if failed. + protected override bool DoFirmwareProgramming(string FilePath, Action Progress) { - if (Options == null) + try { - return null; + IHex Hex = new IHex(); + Hex.load(FilePath); + + Uploader UL = new Uploader(); + UL.ProgressEvent += (d) => Progress(null, d); + UL.upload(_Session.Port, Hex); + _Session.AssumeMode(TSession.TMode.TRANSPARENT); + return true; } - else + catch { - return RFDLib.Array.CherryPickArray(Options, (x) => x.OptionName); + return false; } } - public string GetOptionNameForValue(string Value) + public override string[] FirmwareFileNameExtensions + { + get + { + return new string[] { "hex", "ihx" }; + } + } + + /// + /// Get the correct object for the modem which is in bootloader mode. + /// + /// The session. Must not be null. + /// null if could not generate modem object + public static RFD900APU GetObjectForModem(TSession Session) { - if (Options != null) + Uploader U = new Uploader(); + U.port = Session.Port; + Uploader.Board Board = Uploader.Board.FAILED; + Uploader.Frequency Freq = Uploader.Frequency.FAILED; + + U.getDevice(ref Board, ref Freq); + switch (Board) { - foreach (var O in Options) - { - if (O.Value.ToString() == Value) - { - return O.OptionName; - } - } + case Uploader.Board.DEVICE_ID_RFD900A: + return new RFD900a(Session); + case Uploader.Board.DEVICE_ID_RFD900P: + return new RFD900p(Session); + case Uploader.Board.DEVICE_ID_RFD900U: + return new RFD900u(Session); + default: + return null; } - return null; } + } - public class TRange + public class RFD900a : RFD900APU + { + public RFD900a(TSession Session) + : base(Session) { - public readonly int Min; - public readonly int Max; - public TRange(int Min, int Max) - { - this.Min = Min; - this.Max = Max; - } } - public class TOption + protected override string[] GetFirmwareSearchTokens() { - public readonly int Value; - public readonly string OptionName; + return new string[] { "RFD900A" }; + } - public TOption(int Value, string OptionName) + public override Uploader.Board Board + { + get { - this.Value = Value; - this.OptionName = OptionName; + return Uploader.Board.DEVICE_ID_RFD900A; } } } - public abstract class RFD900 + public class RFD900p : RFD900APU { - protected TSession _Session; - - public RFD900(TSession Session) + public RFD900p(TSession Session) + : base(Session) { - _Session = Session; + } - public abstract bool ProgramFirmware(string FilePath, Action Progress); + protected override string[] GetFirmwareSearchTokens() + { + return new string[] { "RFD900P" }; + } - static bool SearchTokenUpdate(byte[] Token, ref int TokenIndex, byte NextByte) + public override Uploader.Board Board { - if (NextByte == Token[TokenIndex]) + get { - if (++TokenIndex >= Token.Length) - { - //Found it. - return true; - } + return Uploader.Board.DEVICE_ID_RFD900P; } - else + } + } + + public class RFD900u : RFD900APU + { + public RFD900u(TSession Session) + : base(Session) + { + + } + + protected override string[] GetFirmwareSearchTokens() + { + return new string[] { "RFD900U" }; + } + + public override Uploader.Board Board + { + get { - TokenIndex = 0; + return Uploader.Board.DEVICE_ID_RFD900U; } - return false; + } + } + + public abstract class RFD900xuxRevN : RFD900 + { + public RFD900xuxRevN(TSession Session) + : base(Session) + { } /// - /// Search the given binary file for the given tokens + /// Get the correct object for the modem which is in bootloader mode. /// - /// The binary file path. Must not be null. - /// The tokens. Must not be null. - /// true if at least one token found, false if not. - protected static bool SearchBinary(string BinFilePath, string[] Tokens) - { - foreach (var Token in Tokens) + /// The session. Must not be null. + /// null if could not generate modem object + public static RFD900xuxRevN GetObjectForModem(TSession Session) + { + Session.Port.Write("\r\n"); + Thread.Sleep(200); + Session.Port.DiscardInBuffer(); + Session.Port.Write("CHIPID\r\n"); + int TokenIndex = Session.WaitForAnyOfTheseTokens(new string[] { "RFD900xSub:1", "RFD900uxSub:1", "RFD900xSub:2", "RFD900uxSub:2"}, 200); + switch (TokenIndex) + { + case 0: + return new RFD900x(Session); + case 1: + return new RFD900ux(Session); + case 2: + return new RFD900X2(Session); + case 3: + return new RFD900UX2(Session); + default: + return null; + } + } + + static bool GetIsLetter(char x) + { + return (((x >= 'a') && (x <= 'z')) || ((x >= 'A') && (x <= 'Z'))); + } + + /// + /// Gets remote country code. + /// + /// + public TCountry GetRemoteCountryCode() + { + return GetCountryCode("R"); + } + + protected abstract int GetCountryCodeRegPosition(); + + TCountry GetCountryCode(string AorR) + { + string Reply = _Session.ATCClient.DoQuery(AorR + "T+C" + GetCountryCodeRegPosition().ToString() + "?", true); + + int CCInt; + + if (int.TryParse(Reply, out CCInt)) { - byte[] BinToken = System.Text.ASCIIEncoding.ASCII.GetBytes(Token); - - using (System.IO.FileStream FS = new System.IO.FileStream(BinFilePath, System.IO.FileMode.Open)) - { - int Byte; - int TokenIndex = 0; - while ((Byte = FS.ReadByte()) != -1) - { - if (SearchTokenUpdate(BinToken, ref TokenIndex, (byte)Byte)) - { - return true; - } - } - } + return (TCountry)CCInt; + } + else + { + return TCountry.NONE; } + } - return false; + public static TCountry[] GetValidCountryLockOptionsForBand(Uploader.Frequency Band) + { + switch (Band) + { + case Uploader.Frequency.FREQ_868: + return new TCountry[] { TCountry.EU, TCountry.India }; + case Uploader.Frequency.FREQ_915: + return new TCountry[] { TCountry.AU, TCountry.US, TCountry.NZ }; + default: + return new TCountry[0]; + } } - /// - /// Search the given hex file for the given tokens. - /// - /// The file to search. Must not be null. - /// The tokens to search for. Must not be null. - /// true if at least one found, false if not found. - protected static bool SearchHex(IHex File, string[] Tokens) + public TCountry[] GetValidCountryLockOptions() + { + return GetValidCountryLockOptionsForBand(GetBand()); + } + + public static bool GetCanBeLockedToCountry(Uploader.Frequency Band, TCountry C) + { + return (new List(GetValidCountryLockOptionsForBand(Band))).Contains(C); + } + + /// + /// Gets local country code. Assumes in AT command mode already. Returns null if no country code detected. + /// + /// + public TCountry GetCountryCode() + { + return GetCountryCode("A"); + } + + public virtual bool WriteCounty(TCountry C) + { + return _Session.ATCClient.DoCommand("AT+C" + GetCountryCodeRegPosition().ToString() + "=" + ((int)C).ToString()); + } + + + /// + protected bool GetIsThisLockedToCountry() { - foreach (var Token in Tokens) + return GetIsCountryLocked(GetCountryCode()); + } + + public static bool GetIsCountryLocked(TCountry C) + { + switch (C) { - int TokenIndex = 0; - byte[] BinToken = System.Text.ASCIIEncoding.ASCII.GetBytes(Token); + case TCountry.NONE: + case TCountry.Undefined: + return false; + default: + return true; + } + } + protected virtual bool SetHigherBaud() + { + return false; + } - foreach (var Part in File.Values) - { - foreach (byte b in Part) - { - if (SearchTokenUpdate(BinToken, ref TokenIndex, b)) - { - return true; - } - } + protected virtual void ReturnToNormalBaud() + { + + } + + bool DoProgramming(string FilePath, Action Progress) + { + _Session.Port.Write("\r"); + Thread.Sleep(100); + _Session.Port.DiscardInBuffer(); + _Session.Port.Write("UPLOAD\r"); + if (_Session.WaitForToken("Ready\r\n", 5000) && _Session.WaitForToken("C", 5000)) + { + try + { + MissionPlanner.Radio.XModem.ProgressEvent += (d) => Progress(null, d); + bool Result = MissionPlanner.Radio.XModem.Upload(FilePath, _Session.Port); + _Session.AssumeMode(TSession.TMode.INIT); + return Result; + } + catch + { + return false; } } - return false; + else + { + return false; + } } - protected abstract string[] GetFirmwareSearchTokens(); + bool TryFirmwareProgrammingOnce(string FilePath, Action Progress) + { + bool Result; + bool HigherBaud; + + HigherBaud = SetHigherBaud(); + + Result = DoProgramming(FilePath, Progress); + + if (HigherBaud) + { + ReturnToNormalBaud(); + } + + return Result; + } - protected void ShowWrongFirmwareMessageBox() + /// + /// Program the given firmware without doing any checks. + /// + /// The path of the firmware file. Must not be null. + /// A function to use to provide real-time feedback about the + /// programming progress. + /// true if successful, false if failed. + protected override bool DoFirmwareProgramming(string FilePath, Action Progress) { - string S = "File doesn't appear to be valid for this radio. Could not find "; - var Tokens = GetFirmwareSearchTokens(); - for (int n = 0; n < Tokens.Length; n++) + while (!TryFirmwareProgrammingOnce(FilePath, Progress)) { - if (n != 0) + switch (System.Windows.Forms.MessageBox.Show("Programming firmware failed. Try again?", "Programming firmware failed. Try again?", System.Windows.Forms.MessageBoxButtons.YesNoCancel)) { - if (n >= (Tokens.Length - 1)) - { - S += " or "; - } - else - { - S += ", "; - } + case System.Windows.Forms.DialogResult.Yes: + break; + case System.Windows.Forms.DialogResult.No: + case System.Windows.Forms.DialogResult.Cancel: + return false; } - S += "\"" + Tokens[n] + "\""; } - - S += " in File."; - - System.Windows.Forms.MessageBox.Show(S); - } - - public abstract Uploader.Board Board { get; } - } - - public abstract class RFD900APU : RFD900 - { - public RFD900APU(TSession Session) - : base(Session) - { - + return true; } - public override bool ProgramFirmware(string FilePath, Action Progress) + /// + /// Check that the firmware is the right type for this modem. + /// + /// The path to the firmware. Must not be null. + /// true if correct, false if not. + protected override bool CheckFirmwareOK(string FilePath) { - try + if (SearchBinary(FilePath, GetFirmwareSearchTokens())) { - IHex Hex = new IHex(); - Hex.load(FilePath); - - if (SearchHex(Hex, GetFirmwareSearchTokens())) - { - Uploader UL = new Uploader(); - UL.ProgressEvent += (d) => Progress(d); - UL.upload(_Session.Port, Hex); - return true; - } - else - { - ShowWrongFirmwareMessageBox(); - return false; - } + return true; } - catch + else { + ShowWrongFirmwareMessageBox(); return false; } } + public enum TCountry + { + NONE = 0, + AU = 1, + NZ = 2, + US = 3, + EU = 4, + PRC = 5, + Ins = 6, + India = 8, + Undefined = 255, + } + } + + public abstract class RFD900xux : RFD900xuxRevN + { + public RFD900xux(TSession Session) + : base(Session) + { + } + /// - /// Get the correct object for the modem which is in bootloader mode. + /// Returns whether the file of the given path is "certified". i.e. Whether it + /// will return whether it is locked to a country using the ATI command. /// - /// The session. Must not be null. - /// null if could not generate modem object - public static RFD900APU GetObjectForModem(TSession Session) + /// The file path. Must not be null. + /// true if certified, false if not. + bool IsFirmwareCertified(string FilePath) { - Uploader U = new Uploader(); - U.port = Session.Port; - Uploader.Board Board = Uploader.Board.FAILED; - Uploader.Frequency Freq = Uploader.Frequency.FAILED; + return SearchBinary(FilePath, new string[] { "HastaLaVistaBaby" }); + } - U.getDevice(ref Board, ref Freq); - switch (Board) - { - case Uploader.Board.DEVICE_ID_RFD900A: - return new RFD900a(Session); - case Uploader.Board.DEVICE_ID_RFD900P: - return new RFD900p(Session); - case Uploader.Board.DEVICE_ID_RFD900U: - return new RFD900u(Session); - case Uploader.Board.DEVICE_ID_RFD900: - return new RFD900old(Session); - case Uploader.Board.DEVICE_ID_HM_TRP: - return new HM_TRP(Session); - case Uploader.Board.DEVICE_ID_HB1060: - return new HB1060(Session); - default: - return null; - } + protected override int GetCountryCodeRegPosition() + { + return 32; } - } - public class RFD900old : RFD900APU - { - public RFD900old(TSession Session) - : base(Session) + protected abstract string GetRefFirmwareResourcePath(); + + /// + /// Unpack the reference firmware embedded into this exe into a temp file and return + /// the path to that file. + /// + /// The path to the temp file containing the ref file. Never null. + string GetRefFirmwarePath() { + string Temp = System.IO.Path.GetTempFileName(); + var assembly = Assembly.GetExecutingAssembly(); + //var resourceName = "RFD900Tools.Properties.Resources.resources.RFDSiK_V3.00_rfd900x.bin"; + //var resourceName = "RFD900Tools.Resources.RFDSiK V3.00 rfd900x.bin"; + var resourceName = GetRefFirmwareResourcePath(); - } + var Names = assembly.GetManifestResourceNames(); + Console.WriteLine(Names.ToString()); - protected override string[] GetFirmwareSearchTokens() - { - return new string[] { "RFD900" }; - } + using (Stream stream = assembly.GetManifestResourceStream(resourceName)) + using (Stream FileStream = System.IO.File.OpenWrite(Temp)) + using (StreamReader reader = new StreamReader(stream)) + using (StreamWriter writer = new StreamWriter(FileStream)) + { + stream.Seek(0, SeekOrigin.Begin); + stream.CopyTo(FileStream); + } - public override Uploader.Board Board + return Temp; + } + + public override string[] FirmwareFileNameExtensions + { + get + { + return new string[] { "bin" }; + } + } + + public override bool WriteCounty(TCountry C) + { + return _Session.ATCClient.DoCommand("AT+C" + GetCountryCodeRegPosition().ToString() + "=" + ((int)C).ToString()); + } + + /// + /// Program the given firmware. Do necesary checks first. + /// + /// The path to the firmware file. Must not be null. + /// The function to call back to provide progress updates. + /// true if successful, false if failed. + public override bool ProgramFirmware(string FilePath, Action Progress) { - get + if (IsFirmwareCertified(FilePath)) { - return Uploader.Board.DEVICE_ID_RFD900; + return base.ProgramFirmware(FilePath, Progress); } - } - } + else + { + Progress("Trying to put into AT command mode.", double.NaN); + if (_Session.PutIntoATCommandMode() != TSession.TMode.AT_COMMAND) + { + Progress("Trying to put into bootloader mode.", double.NaN); + if (_Session.PutIntoBootloaderMode() == TSession.TMode.BOOTLOADER_X) + { + Progress("Programming temporary firmware into modem to check certified.", double.NaN); + string RefFirmwarePath = GetRefFirmwarePath(); + try + { + if (!DoFirmwareProgramming(RefFirmwarePath, Progress)) + { + return false; + } + } + finally + { + try + { + System.IO.File.Delete(RefFirmwarePath); + } + catch + { + + } + } + } + else + { + return false; + } + } - public class RFD900a : RFD900APU + //Can it go into AT command mode? + Progress("Trying to put into AT command mode.", double.NaN); + if (_Session.PutIntoATCommandMode() == TSession.TMode.AT_COMMAND) + { + Progress("Checking if modem certified.", double.NaN); + if (!GetIsThisLockedToCountry()) + { + //They can program whatever they want into it. + return base.ProgramFirmware(FilePath, Progress); + } + else + { + //They can only program certified firmware into it. + if (IsFirmwareCertified(FilePath)) + { + return base.ProgramFirmware(FilePath, Progress); + } + else + { + System.Windows.Forms.MessageBox.Show("The selected firmware is not certified to run on this modem. Aborting."); + return false; + } + } + } + else + { + return false; + } + } + } + } + + public class RFD900x : RFD900xux { - public RFD900a(TSession Session) + public RFD900x(TSession Session) : base(Session) { } + protected override string GetRefFirmwareResourcePath() + { + return "RFD900Tools.Resources.RFDSiK V3.01 rfd900x.bin"; + } + protected override string[] GetFirmwareSearchTokens() { - return new string[] { "RFD900A" }; + return new string[] { "RFD900x", "RFD900X" }; } public override Uploader.Board Board { get { - return Uploader.Board.DEVICE_ID_RFD900A; + return Uploader.Board.DEVICE_ID_RFD900X; } } } @@ -1044,157 +2571,205 @@ public override Uploader.Board Board } } - - public class RFD900p : RFD900APU + public class RFD900ux : RFD900xux { - public RFD900p(TSession Session) + public RFD900ux(TSession Session) : base(Session) { } - protected override string[] GetFirmwareSearchTokens() - { - return new string[] { "RFD900P" }; + protected override string GetRefFirmwareResourcePath() + { + return "RFD900Tools.Resources.RFDSiK V3.08 rfd900ux.bin"; } public override Uploader.Board Board { get { - return Uploader.Board.DEVICE_ID_RFD900P; + return Uploader.Board.DEVICE_ID_RFD900UX; } } + + protected override string[] GetFirmwareSearchTokens() + { + return new string[] { "RFD900ux", "RFD900UX" }; + } } - public class RFD900u : RFD900APU - { - public RFD900u(TSession Session) + /*public class RFD900sx : RFD900xux + { + public RFD900sx(TSession Session) : base(Session) { + } + + protected override string[] GetFirmwareSearchTokens() + { + return new string[] { "RFD900sx", "RFD900SX" }; + } + }*/ + public abstract class RFD900xuxRev2 : RFD900xuxRevN + { + public RFD900xuxRev2(TSession Session) + : base(Session) + { } - protected override string[] GetFirmwareSearchTokens() - { - return new string[] { "RFD900U" }; + protected override int GetCountryCodeRegPosition() + { + return 51; } - public override Uploader.Board Board - { - get - { - return Uploader.Board.DEVICE_ID_RFD900U; - } + protected override bool CheckFirmwareOK(string FilePath) + { + return true; + } + + protected override string[] GetFirmwareSearchTokens() + { + return new string[0]; + } + + protected override bool SetHigherBaud() + { + _Session.WriteToPort("BAUDHI\r\n"); + + bool Result = _Session.WaitForToken("OK", 500); + + if (Result) + { + _Session.Port.BaudRate = 1200000; + } + + return Result; + } + + protected override void ReturnToNormalBaud() + { + _Session.WriteToPort("BAUDLO\r\n"); + _Session.WaitForToken("OK", 500); + _Session.Port.BaudRate = 57600; + } + + public override bool WriteCounty(TCountry C) + { + return base.WriteCounty(C) && + _Session.ATCClient.DoCommand("AT+LC"); + } + + public override string[] FirmwareFileNameExtensions + { + get + { + return new string[] { "gbl" }; + } } } - public abstract class RFD900xux : RFD900 + public class RFD900X2 : RFD900xuxRev2 { - public RFD900xux(TSession Session) + public RFD900X2(TSession Session) : base(Session) { - } - /// - /// Get the correct object for the modem which is in bootloader mode. - /// - /// The session. Must not be null. - /// null if could not generate modem object - public static RFD900xux GetObjectForModem(TSession Session) - { - Session.Port.Write("\r\n"); - Thread.Sleep(200); - Session.Port.DiscardInBuffer(); - Session.Port.Write("CHIPID\r\n"); - int TokenIndex = Session.WaitForAnyOfTheseTokens(new string[] { "RFD900x", "RFD900ux" }, 200); - switch (TokenIndex) + public override Uploader.Board Board + { + get { - case 0: - return new RFD900x(Session); - case 1: - return new RFD900ux(Session); - default: - return null; - } + return Uploader.Board.DEVICE_ID_RFD900X2; + } } - - public override bool ProgramFirmware(string FilePath, Action Progress) + } + + public class RFD900UX2 : RFD900xuxRev2 + { + public RFD900UX2(TSession Session) + : base(Session) { - if (SearchBinary(FilePath, GetFirmwareSearchTokens())) - { - _Session.Port.Write("\r"); - Thread.Sleep(100); - _Session.Port.DiscardInBuffer(); - _Session.Port.Write("UPLOAD\r"); - if (_Session.WaitForToken("Ready\r\n", 5000) && _Session.WaitForToken("C", 5000)) - { - try - { - MissionPlanner.Radio.XModem.ProgressEvent += (d) => Progress(d); - MissionPlanner.Radio.XModem.Upload(FilePath, _Session.Port); - return true; - } - catch - { - return false; - } - } - else - { - return false; - } - } - else - { - ShowWrongFirmwareMessageBox(); - return false; - } + } + + public override Uploader.Board Board + { + get + { + return Uploader.Board.DEVICE_ID_RFD900UX2; + } } } - public class RFD900x : RFD900xux + /// + /// A RFDLib.IO.TSerialPort wrapper for TMissionPlannerSerialPort + /// + public class TMissionPlannerSerialPort : RFDLib.IO.TSerialPort { - public RFD900x(TSession Session) - : base(Session) + MissionPlanner.Comms.ICommsSerial _Port; + + public TMissionPlannerSerialPort(MissionPlanner.Comms.ICommsSerial Port) + { + _Port = Port; + } + + public override void Write(string Text) { + _Port.Write(Text); + } + public override void DiscardInBuffer() + { + _Port.DiscardInBuffer(); } - protected override string[] GetFirmwareSearchTokens() + public override int ReadChar() { - return new string[] { "RFD900x", "RFD900X" }; + return _Port.ReadChar(); } - public override Uploader.Board Board + public override string ReadExisting() + { + return _Port.ReadExisting(); + } + + public override string ReadLine() + { + return _Port.ReadLine(); + } + + public override int ReadTimeout { get { - return Uploader.Board.DEVICE_ID_RFD900X; + return _Port.ReadTimeout; + } + set + { + _Port.ReadTimeout = value; } } } - public class RFD900ux : RFD900xux + public class TATCClient : RFDLib.IO.ATCommand.TClient { - public RFD900ux(TSession Session) - : base(Session) - { - + public TATCClient(RFDLib.IO.TSerialPort Port) + : base(Port) + { } - public override Uploader.Board Board + public override string DoQuery(string Command, bool WaitForTerminator) { - get + string Raw = base.DoQuery(Command, WaitForTerminator); + + if (Raw.StartsWith("[") && Raw.Contains("]") && ((Raw.IndexOf(']') + 1) < Raw.Length)) { - return Uploader.Board.DEVICE_ID_RFD900UX; + return Raw.Substring(Raw.IndexOf(']') + 1); + } + else + { + return Raw; } - } - - protected override string[] GetFirmwareSearchTokens() - { - return new string[] { "RFD900ux", "RFD900UX" }; } } } \ No newline at end of file diff --git a/SikRadio/RFDLib/Array.cs b/SikRadio/RFDLib/Array.cs index 213f1163cf..7f4da5be74 100644 --- a/SikRadio/RFDLib/Array.cs +++ b/SikRadio/RFDLib/Array.cs @@ -13,6 +13,30 @@ public static T[] CherryPickArray(U[] x, Func PickFn) Result[n] = PickFn(x[n]); } return Result; + } + + /// + /// Copy the given array, removing elements which meet the given condition. + /// + /// + /// + /// + /// + public static T[] ConditionalRemove(T[] x, Func Condition) + { + T[] Temp = new T[x.Length]; + int Length = 0; + foreach (var a in x) + { + if (!Condition(a)) + { + Temp[Length++] = a; + } + } + + T[] Result = new T[Length]; + System.Array.Copy(Temp, Result, Length); + return Result; } } } diff --git a/SikRadio/RFDLib/Collections.cs b/SikRadio/RFDLib/Collections.cs new file mode 100644 index 0000000000..3db3b7b1a5 --- /dev/null +++ b/SikRadio/RFDLib/Collections.cs @@ -0,0 +1,36 @@ +using System; +using System.Collections.Generic; + +namespace RFDLib +{ + public static class Collections + { + public static Dictionary Translate(Dictionary x, Func TransLateFn) + { + Dictionary Result = new Dictionary(); + + foreach (var kvp in x) + { + Result[kvp.Key] = TransLateFn(kvp.Value); + } + + return Result; + } + + /// + /// Update the given original dictionary with new values from NewValues. + /// + /// + /// + /// + /// + public static void Update(Dictionary Original, Dictionary NewValues) + { + foreach (var kvp in NewValues) + { + Original[kvp.Key] = kvp.Value; + } + } + } + +} \ No newline at end of file diff --git a/SikRadio/RFDLib/GUI/Settings.cs b/SikRadio/RFDLib/GUI/Settings.cs new file mode 100644 index 0000000000..183c0582c7 --- /dev/null +++ b/SikRadio/RFDLib/GUI/Settings.cs @@ -0,0 +1,262 @@ +using System; +using System.Collections.Generic; +using System.Windows.Forms; + +namespace RFDLib.GUI.Settings +{ + public class TLabelEditorPair + { + public readonly Label L; + public readonly Control Editor; + + public TLabelEditorPair(Label L, Control Editor) + { + this.L = L; + this.Editor = Editor; + } + + public virtual string[] SettingNames + { + get + { + return new string[] { Editor.Name }; + } + } + } + + /// + /// A TLabelEditorPair which remembers the original name and label. + /// + public class TOrigLabelEditorPair : TLabelEditorPair + { + public readonly string OriginalLabel; + public readonly string OriginalName; + public readonly bool OrigVisible; + public readonly ToolTip OrigToolTip; + public readonly string OrigToolTipText; + + public TOrigLabelEditorPair(Label L, Control Editor, ToolTip TT) + : base(L, Editor) + { + this.OriginalLabel = L.Text; + this.OriginalName = Editor.Name; + this.OrigVisible = Editor.Visible; + this.OrigToolTip = TT; + this.OrigToolTipText = TT.GetToolTip(Editor); + } + + /// + /// Reset to original values. + /// + public void Reset() + { + L.Text = OriginalLabel; + Editor.Name = OriginalName; + L.Visible = OrigVisible; + Editor.Visible = OrigVisible; + OrigToolTip.SetToolTip(Editor, OrigToolTipText); + } + } + + /// + /// This is for dynamically re-using spare label-editor pairs for which there is no setting in the modem. + /// + public class TLabelEditorPairRegister + { + Dictionary _Pairs = new Dictionary(); + Dictionary _Spare = new Dictionary(); + + /// + /// Add a label-editor pair. + /// + /// + public void Add(TOrigLabelEditorPair Pair) + { + _Pairs[Pair.OriginalName] = Pair; + } + + /// + /// Add a label-editor pair. + /// + /// + /// + public void Add(Label L, Control Editor, ToolTip TT) + { + Add(new TOrigLabelEditorPair(L, Editor, TT)); + } + + /// + /// Reset all label-editor pairs to their original labels and names. + /// + public void Reset() + { + foreach (var P in _Pairs.Values) + { + P.Reset(); + } + + _Spare.Clear(); + } + + /// + /// Call this when the list of setting names has been read from the modem, so the spare + /// label-editor pairs can be put into a separate list. + /// + /// The list of setting names read from the modem. Must not be null. + public void SetUp(List SettingNamesSet) + { + foreach (var kvp in _Pairs) + { + if (!SettingNamesSet.Contains(kvp.Value.Editor.Name)) + { + _Spare[kvp.Key] = kvp.Value; + } + } + } + + /// + /// Get a spare editor control for an unexpected setting read from the modem. Set the editor's label + /// to the setting name, if a spare editor was found. + /// + /// The setting name. Must not be null. + /// The condition the editor control must meet. Must not be null. + /// + Control GetSpare(string SettingName, Func Condition, string Description) + { + TOrigLabelEditorPair Pair = null; + + foreach (var kvp in _Spare) + { + if (Condition(kvp.Value.Editor)) + { + //Assign to a variable and break, instead of processing here, because + //part of the processing is removing it from _Spare, but _Spare is being iterated here. + Pair = kvp.Value; + break; + } + } + + if (Pair == null) + { + return null; + } + else + { + Pair.Editor.Name = SettingName; + Pair.L.Text = Description; + if (Pair.L.Bottom > Pair.Editor.Top) + { + while (Pair.L.Width > (Pair.Editor.Left - Pair.L.Left) && Pair.L.Font.Size > 1) + { + Pair.L.Font = new System.Drawing.Font(Pair.L.Font.FontFamily, Pair.L.Font.Size - 1); + } + } + Pair.L.Visible = true; + Pair.Editor.Visible = true; + Pair.OrigToolTip.SetToolTip(Pair.Editor, Description); + _Spare.Remove(Pair.OriginalName); + return Pair.Editor; + } + } + + /// + /// Return a spare combobox if there is one, otherwise return null. + /// + /// + /// + public ComboBox GetSpareComboBox(string SettingName, string Description) + { + return (ComboBox)GetSpare(SettingName, (C) => C is ComboBox, Description); + } + + /// + /// Return a spare checkbox if there is one, otherwise return null. + /// + /// + /// + public CheckBox GetSpareCheckbox(string SettingName, string Description) + { + return (CheckBox)GetSpare(SettingName, (C) => C is CheckBox, Description); + } + } + + public class TDynamicLabelEditorPair : TLabelEditorPair + { + public readonly TSettingNameLabelTextPair[] AlternateNames; + + public TDynamicLabelEditorPair(Label L, Control Editor, TSettingNameLabelTextPair[] AlternateNames) + : base(L, Editor) + { + this.AlternateNames = AlternateNames; + } + + public override string[] SettingNames + { + get + { + string[] Result = new string[AlternateNames.Length]; + + for (int n = 0; n < AlternateNames.Length; n++) + { + Result[n] = AlternateNames[n].SettingName; + } + + return Result; + } + } + + public bool SetUpForSettingName(string SettingName) + { + foreach (var SNLTP in AlternateNames) + { + if (SNLTP.SettingName == SettingName) + { + L.Text = SNLTP.LabelText; + return true; + } + } + + return false; + } + + public class TSettingNameLabelTextPair + { + public readonly string SettingName; + public readonly string LabelText; + + public TSettingNameLabelTextPair(string SettingName, string LabelText) + { + this.SettingName = SettingName; + this.LabelText = LabelText; + } + } + } + + public class TDynamicLabelEditorPairRegister + { + public readonly TDynamicLabelEditorPair[] Pairs; + + public TDynamicLabelEditorPairRegister(TDynamicLabelEditorPair[] Pairs) + { + this.Pairs = Pairs; + } + + /// + /// Try to find an editor control for the setting of the given name, and if found, set up its label. + /// Returns the editor control if successful, otherwise returns null. + /// + /// The setting name. Must not be null. + /// Returns the editor control if successful, otherwise returns null. + public Control FindAndSetUpEditorWithSettingName(string SettingName) + { + foreach (var Pair in Pairs) + { + if (Pair.SetUpForSettingName(SettingName)) + { + return Pair.Editor; + } + } + return null; + } + } +} \ No newline at end of file diff --git a/SikRadio/RFDLib/IO/ATCommand.cs b/SikRadio/RFDLib/IO/ATCommand.cs new file mode 100644 index 0000000000..5aa01b105d --- /dev/null +++ b/SikRadio/RFDLib/IO/ATCommand.cs @@ -0,0 +1,209 @@ +using System; + +namespace RFDLib.IO.ATCommand +{ + /// + /// An AT-command interface client. + /// + public class TClient + { + public IO.TSerialPort _Port; + /// + /// The line terminator. null if nothing. + /// + public string Terminator = "\r\n"; + /// + /// true if the server echoes commands, and the echoes need to be ignored. + /// + public bool Echoes = true; + /// + /// The maximum time to wait for a response. + /// + public int Timeout = 2000; + + /// + /// Create a new TClient + /// + /// The serial port to use. Must not be null. + public TClient(IO.TSerialPort Port) + { + _Port = Port; + } + + /// + /// Returns the terminator to use. + /// + /// The terminator to use, never null. + string GetTerminator() + { + if (Terminator == null) + { + return ""; + } + else + { + return Terminator; + } + } + + /// + /// Get next char from serial port. Wait up to the read timeout. + /// + /// the char read + /// true if got char before timeout, false if not. + bool GetNextChar(out char x) + { + try + { + x = (char)_Port.ReadChar(); + return true; + } + catch + { + x = '\0'; + return false; + } + } + + /// + /// Eliminate the command echo. + /// + /// The complete command including terminator. Must not be null. + /// true if got echo OK, false if not. + bool EliminateEcho(string CompleteCommand) + { + if (Echoes) + { + _Port.ReadTimeout = Timeout; + int n = 0; + char Temp; + while ((n < CompleteCommand.Length) && GetNextChar(out Temp)) + { + if (CompleteCommand[n] == Temp) + { + n++; + } + else + { + return false; + } + } + } + return true; + } + + /// + /// Do a command and wait for a reply. Returns true if "OK" + /// + /// + /// + public bool DoCommand(string Command) + { + string Result = DoQuery(Command, true); + return Result.Contains("OK"); + } + + /// + /// Returns a received line from the interface. + /// + /// + public string GetLine() + { + return _Port.ReadLine(); + } + + /// + /// Do the given command. If wait for terminator, returns the result minus + /// the terminator. + /// + /// The command. Must not be null. + /// true to wait for terminator. + /// The reply, except for the echo. + public virtual string DoQuery(string Command, bool WaitForTerminator) + { + string CompleteCommand = Command + GetTerminator(); + _Port.DiscardInBuffer(); + _Port.Write(CompleteCommand); + if (EliminateEcho(CompleteCommand)) + { + string Result; + if (WaitForTerminator) + { + if (IO.TSerialPort.WaitForToken(_Port, Terminator, Timeout, out Result)) + { + //Get the terminator out of it. + return Result.Split(new string[] { Terminator }, StringSplitOptions.None)[0]; + } + else + { + return Result; + } + } + else + { + IO.TSerialPort.WaitForToken(_Port, null, Timeout, out Result); + return Result; + } + } + else + { + return ""; + } + } + + public string DoQueryWithMultiLineResponse(string Command) + { + string CompleteCommand = Command + GetTerminator(); + _Port.DiscardInBuffer(); + _Port.Write(CompleteCommand); + + if (EliminateEcho(CompleteCommand)) + { + string Result = ""; + string Temp; + int Timeout = this.Timeout; + + while (IO.TSerialPort.WaitForToken(_Port, Terminator, Timeout, out Temp)) + { + Result += Temp; + Timeout = 500; + } + + return Result; + } + else + { + return ""; + } + } + } + + public class TServer + { + TSerialPort _Port; + public event Action GotCommand; + + public TServer(TSerialPort Port) + { + _Port = Port; + } + + public abstract class TCommand + { + } + + public class TQuery : TCommand + { + public char FirstCharacter; + public string Parameter; + } + + public class TSetValue : TCommand + { + public char FirstCharacter; + public string Parameter; + public string Value; + } + + } +} \ No newline at end of file diff --git a/SikRadio/RFDLib/IO/SerialPort/SerialPort.cs b/SikRadio/RFDLib/IO/SerialPort/SerialPort.cs new file mode 100644 index 0000000000..a2ea7f4c55 --- /dev/null +++ b/SikRadio/RFDLib/IO/SerialPort/SerialPort.cs @@ -0,0 +1,137 @@ +using System; + +namespace RFDLib.IO +{ + public abstract class TSerialPort + { + public abstract void Write(string Text); + public abstract string ReadExisting(); + public abstract int ReadTimeout { get; set; } + public abstract int ReadChar(); + public abstract string ReadLine(); + public abstract void DiscardInBuffer(); + + /// + /// Query a serial port. + /// + /// The port. Must not be null. + /// The query to send, without the terminator. Must not be null. + /// The terminator. Can be null if none. + /// The maximum period to wait in milliseconds. + /// The data returned. Never null. + public static string Query(TSerialPort Port, + string Query, string Terminator, int MaxWait) + { + Port.DiscardInBuffer(); + Query = Query + (Terminator == null ? "" : Terminator); + Port.Write(Query); + string Reply; + WaitForToken(Port, Terminator, MaxWait, out Reply); + return Reply; + } + + /// + /// Wait for the given token or timeout on the given serial port. + /// + /// The port. Must not be null. + /// The token to wait for. Can be null if not waiting for a token. + /// The maximum amount of time to wait for a response, in milliseconds. + /// true if token was received, false if not. + public static bool WaitForToken(TSerialPort Port, + string Token, int MaxWait) + { + string Temp; + return WaitForToken(Port, Token, MaxWait, out Temp); + } + + /// + /// Wait for the given token or timeout on the given serial port + /// + /// The port. Must not be null. + /// The token to wait for. Can be null if not waiting for a token. + /// The maximum amount of time to wait for a response, in milliseconds. + /// The data returned. Never null. + /// true if token was received, false if not. + public static bool WaitForToken(TSerialPort Port, + string Token, int MaxWait, out string Result) + { + System.Diagnostics.Stopwatch SW = new System.Diagnostics.Stopwatch(); + string Temp = ""; + int Timeout = Port.ReadTimeout; + Port.ReadTimeout = MaxWait; + SW.Start(); + + while (SW.ElapsedMilliseconds < MaxWait) + { + //System.Diagnostics.Stopwatch StWa = new System.Diagnostics.Stopwatch(); + //SW.Start(); + string x = Port.ReadExisting(); + //if (StWa.ElapsedMilliseconds > 10) + //{ + // System.Diagnostics.Debug.WriteLine("Read existing slow\n"); + //} + Temp += x; + + if ((Token != null) && Temp.Contains(Token)) + { + Port.ReadTimeout = Timeout; + Result = Temp; + return true; + } + + System.Threading.Thread.Sleep(50); + } + Port.ReadTimeout = Timeout; + Result = Temp; + return false; + } + } + + public class TSystemIOPortsSerialPort : TSerialPort + { + System.IO.Ports.SerialPort _Port; + + public TSystemIOPortsSerialPort(System.IO.Ports.SerialPort Port) + { + _Port = Port; + } + + public override void DiscardInBuffer() + { + _Port.DiscardInBuffer(); + } + + public override int ReadChar() + { + return _Port.ReadChar(); + } + + public override void Write(string Text) + { + _Port.Write(Text); + } + + public override string ReadLine() + { + return _Port.ReadLine(); + } + + public override string ReadExisting() + { + return _Port.ReadExisting(); + } + + public override int ReadTimeout + { + get + { + return _Port.ReadTimeout; + } + set + { + _Port.ReadTimeout = value; + } + } + } + +} \ No newline at end of file diff --git a/SikRadio/RFDLib/RFDLib.cs b/SikRadio/RFDLib/RFDLib.cs new file mode 100644 index 0000000000..565554647e --- /dev/null +++ b/SikRadio/RFDLib/RFDLib.cs @@ -0,0 +1,49 @@ +using System; + + +namespace RFDLib +{ + + public static class Utils + { + + public static bool Retry(Func ToTry, Func PassedCondition, int QTYTries) + { + int TryCount; + + for (TryCount = 0; TryCount < QTYTries; TryCount++) + { + if (PassedCondition(ToTry())) + { + return true; + } + } + + return false; + } + + public static bool Retry(Func PassedCondition, int QTYTries) + { + return Retry(() => (int)1, (x) => PassedCondition(), QTYTries); + } + + public static System.Collections.Generic.KeyValuePair[] EnumToStrings(Type EnumType) + { + var Values = Enum.GetValues(EnumType); + System.Collections.Generic.KeyValuePair[] Result = + new System.Collections.Generic.KeyValuePair[Values.Length]; + + for (int n = 0; n < Values.Length; n++) + { + Result[n] = new System.Collections.Generic.KeyValuePair( + Enum.GetName(EnumType, Values.GetValue(n)), (int)Values.GetValue(n)); + + } + + return Result; + } + + } + + +} \ No newline at end of file diff --git a/SikRadio/RFDLib/Text.cs b/SikRadio/RFDLib/Text.cs index 57fcfb8e72..9cba4abd0d 100644 --- a/SikRadio/RFDLib/Text.cs +++ b/SikRadio/RFDLib/Text.cs @@ -3,7 +3,18 @@ namespace RFDLib { public static class Text - { + { + /// + /// Case-insensitive contains. + /// + /// + /// + /// + public static bool Contains(string Haystack, string Needle) + { + return Haystack.IndexOf(Needle, StringComparison.OrdinalIgnoreCase) >= 0; + } + /// /// Returns whether the given character is an upper or lower case letter of the alphabet. /// @@ -23,5 +34,10 @@ public static bool CheckIsNumeral(char c) { return (c >= '0' && c <= '9'); } + + public static bool CheckIsHexNumeral(char c) + { + return CheckIsNumeral(c) || (c >= 'a' && c <= 'f') || (c >= 'A' && c <= 'F'); + } } } \ No newline at end of file diff --git a/SikRadio/Resources/RFDSiK V3.00 rfd900x.bin b/SikRadio/Resources/RFDSiK V3.00 rfd900x.bin new file mode 100644 index 0000000000..c360ac31c3 Binary files /dev/null and b/SikRadio/Resources/RFDSiK V3.00 rfd900x.bin differ diff --git a/SikRadio/Resources/RFDSiK V3.01 rfd900x.bin b/SikRadio/Resources/RFDSiK V3.01 rfd900x.bin new file mode 100644 index 0000000000..fea1b4569c Binary files /dev/null and b/SikRadio/Resources/RFDSiK V3.01 rfd900x.bin differ diff --git a/SikRadio/Resources/RFDSiK V3.08 rfd900ux.bin b/SikRadio/Resources/RFDSiK V3.08 rfd900ux.bin new file mode 100644 index 0000000000..ed142e57d1 Binary files /dev/null and b/SikRadio/Resources/RFDSiK V3.08 rfd900ux.bin differ diff --git a/SikRadio/Rssi.Designer.cs b/SikRadio/Rssi.Designer.cs index e68973c03a..028199b06c 100644 --- a/SikRadio/Rssi.Designer.cs +++ b/SikRadio/Rssi.Designer.cs @@ -1,4 +1,4 @@ -using MissionPlanner.Controls; +using MissionPlanner.Controls; namespace SikRadio { partial class Rssi @@ -32,8 +32,6 @@ private void InitializeComponent() this.components = new System.ComponentModel.Container(); this.zedGraphControl1 = new ZedGraph.ZedGraphControl(); this.timer1 = new System.Windows.Forms.Timer(this.components); - this.BUT_disconnect = new MissionPlanner.Controls.MyButton(); - this.BUT_connect = new MissionPlanner.Controls.MyButton(); this.SuspendLayout(); // // zedGraphControl1 @@ -57,37 +55,9 @@ private void InitializeComponent() // this.timer1.Tick += new System.EventHandler(this.timer1_Tick); // - // BUT_disconnect - // - this.BUT_disconnect.Anchor = System.Windows.Forms.AnchorStyles.Top; - this.BUT_disconnect.Enabled = false; - this.BUT_disconnect.Location = new System.Drawing.Point(250, 4); - this.BUT_disconnect.Name = "BUT_disconnect"; - this.BUT_disconnect.Size = new System.Drawing.Size(75, 23); - this.BUT_disconnect.TabIndex = 2; - this.BUT_disconnect.Text = "Disconnect"; - this.BUT_disconnect.UseVisualStyleBackColor = true; - this.BUT_disconnect.Visible = false; - this.BUT_disconnect.Click += new System.EventHandler(this.BUT_disconnect_Click); - // - // BUT_connect - // - this.BUT_connect.Anchor = System.Windows.Forms.AnchorStyles.Top; - this.BUT_connect.Location = new System.Drawing.Point(169, 4); - this.BUT_connect.Name = "BUT_connect"; - this.BUT_connect.Size = new System.Drawing.Size(75, 23); - this.BUT_connect.TabIndex = 1; - this.BUT_connect.Text = "Connect"; - this.BUT_connect.UseVisualStyleBackColor = true; - this.BUT_connect.Visible = false; - this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click); - // // Rssi // this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.None; - - this.Controls.Add(this.BUT_disconnect); - this.Controls.Add(this.BUT_connect); this.Controls.Add(this.zedGraphControl1); this.Name = "Rssi"; this.Size = new System.Drawing.Size(492, 386); @@ -98,8 +68,7 @@ private void InitializeComponent() #endregion private ZedGraph.ZedGraphControl zedGraphControl1; - private MyButton BUT_connect; - private MyButton BUT_disconnect; private System.Windows.Forms.Timer timer1; } } + diff --git a/SikRadio/Rssi.cs b/SikRadio/Rssi.cs index 53b022cc69..21c202a807 100644 --- a/SikRadio/Rssi.cs +++ b/SikRadio/Rssi.cs @@ -32,24 +32,48 @@ public Rssi() zedGraphControl1.GraphPane.Title.Text = "RSSI"; - if (Terminal.sw == null) - Terminal.sw = new StreamWriter("Terminal-" + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".txt"); + Terminal.SetupStreamWriter(); } public void Connect() { if (_Session == null) { - _Session = new RFD.RFD900.TSession(SikRadio.Config.comPort); - if (_Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND) + RFD.RFD900.TSession Session = null; + + if (RFDLib.Utils.Retry(() => + { + Session = new RFD.RFD900.TSession(SikRadio.Config.comPort, MainV2.comPort.BaseStream.BaudRate); + return Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND; + } + , 3)) { - inter.doCommand(Config.comPort, "AT&T=RSSI"); + if (RFDLib.Utils.Retry(() => Session.ATCClient.DoQuery("AT&T=RSSI", true).Contains("RSSI"), 3)) + { + Session.AssumeMode(RFD.RFD900.TSession.TMode.TRANSPARENT); - _Session.AssumeMode(RFD.RFD900.TSession.TMode.TRANSPARENT); + tickStart = Environment.TickCount; - tickStart = Environment.TickCount; + timer1.Start(); - timer1.Start(); + _Session = Session; + } + else + { + var ATIReply = Session.ATCClient.DoQuery("ATI", true); + if (RFDLib.Text.Contains(ATIReply, "async")) + { + MissionPlanner.MsgBox.CustomMessageBox.Show("Firmware doesn't support RSSI reporting"); + } + else + { + MissionPlanner.MsgBox.CustomMessageBox.Show("Failed to enter RSSI reporting mode."); + } + } + } + else + { + MissionPlanner.MsgBox.CustomMessageBox.Show("Failed to put modem into AT command mode."); } } } @@ -70,62 +94,10 @@ public void Disconnect() _Session.Dispose(); _Session = null; - - BUT_disconnect.Enabled = false; - BUT_connect.Enabled = true; } } } - private void BUT_connect_Click(object sender, EventArgs e) - { - CustomMessageBox.Show("Ensure you disconnect properly, to leave the radio in a good state"); - - try - { - MainV2.comPort.BaseStream.Open(); - - inter.doConnect(MainV2.comPort.BaseStream); - - inter.doCommand(MainV2.comPort.BaseStream, "AT&T=RSSI"); - - inter.doCommand(MainV2.comPort.BaseStream, "ATO"); - - tickStart = Environment.TickCount; - - timer1.Start(); - - BUT_disconnect.Enabled = true; - BUT_connect.Enabled = false; - } - catch - { - CustomMessageBox.Show("Bad Port Setting"); - } - } - - private void BUT_disconnect_Click(object sender, EventArgs e) - { - try - { - timer1.Stop(); - - inter.doConnect(MainV2.comPort.BaseStream); - - inter.doCommand(MainV2.comPort.BaseStream, "AT&T"); - - inter.doCommand(MainV2.comPort.BaseStream, "ATO"); - - MainV2.comPort.BaseStream.Close(); - - BUT_disconnect.Enabled = false; - BUT_connect.Enabled = true; - } - catch - { - } - } - private void timer1_Tick(object sender, EventArgs e) { var comPort = SikRadio.Config.comPort; @@ -137,40 +109,54 @@ private void timer1_Tick(object sender, EventArgs e) if (comPort.BytesToRead < 50) return; - var line = comPort.ReadLine(); + try + { + var line = comPort.ReadLine(); - /* -L/R RSSI: 12/0 L/R noise: 17/0 pkts: 0 txe=0 rxe=0 stx=0 srx=0 ecc=0/0 temp=61 dco=0 -L/R RSSI: 12/0 L/R noise: 16/0 pkts: 0 txe=0 rxe=0 stx=0 srx=0 ecc=0/0 temp=61 dco=0 - */ + /* + L/R RSSI: 12/0 L/R noise: 17/0 pkts: 0 txe=0 rxe=0 stx=0 srx=0 ecc=0/0 temp=61 dco=0 + L/R RSSI: 12/0 L/R noise: 16/0 pkts: 0 txe=0 rxe=0 stx=0 srx=0 ecc=0/0 temp=61 dco=0 + */ - var rssi = new Regex(@"RSSI: ([0-9]+)/([0-9]+)\s+L/R noise: ([0-9]+)/([0-9]+)"); + var rssi = new Regex(@"RSSI: ([0-9]+)/([0-9]+)\s+L/R noise: ([0-9]+)/([0-9]+)"); - var match = rssi.Match(line); + var match = rssi.Match(line); - if (match.Success) - { - var time = (Environment.TickCount - tickStart)/1000.0; + if (match.Success) + { + var time = (Environment.TickCount - tickStart) / 1000.0; - plotdatarssil.Add(time, double.Parse(match.Groups[1].Value)); - plotdatarssir.Add(time, double.Parse(match.Groups[2].Value)); - plotdatanoicel.Add(time, double.Parse(match.Groups[3].Value)); - plotdatanoicer.Add(time, double.Parse(match.Groups[4].Value)); + plotdatarssil.Add(time, double.Parse(match.Groups[1].Value)); + plotdatarssir.Add(time, double.Parse(match.Groups[2].Value)); + plotdatanoicel.Add(time, double.Parse(match.Groups[3].Value)); + plotdatanoicer.Add(time, double.Parse(match.Groups[4].Value)); - // Make sure the Y axis is rescaled to accommodate actual data - zedGraphControl1.AxisChange(); + // Make sure the Y axis is rescaled to accommodate actual data + zedGraphControl1.AxisChange(); - // Force a redraw + // Force a redraw - zedGraphControl1.Invalidate(); + zedGraphControl1.Invalidate(); - if (Terminal.sw != null) - { - Terminal.sw.Write(line); - Terminal.sw.Flush(); + if (Terminal.sw != null) + { + Terminal.sw.Write(line); + Terminal.sw.Flush(); + } } } + catch + { + } + } + } + + public string Header + { + get + { + return "RSSI"; } } } diff --git a/SikRadio/SikRadio.csproj b/SikRadio/SikRadio.csproj index 992a3f2f91..9ecc061046 100644 --- a/SikRadio/SikRadio.csproj +++ b/SikRadio/SikRadio.csproj @@ -118,6 +118,7 @@ Linked\XModem.cs + Form @@ -133,6 +134,11 @@ + + + + + UserControl @@ -228,6 +234,9 @@ Designer + + + diff --git a/SikRadio/Terminal.cs b/SikRadio/Terminal.cs index 4cdac91d33..2fc4128831 100644 --- a/SikRadio/Terminal.cs +++ b/SikRadio/Terminal.cs @@ -22,6 +22,11 @@ public Terminal() { InitializeComponent(); + SetupStreamWriter(); + } + + public static void SetupStreamWriter() + { if (sw == null) sw = new StreamWriter(Environment.GetFolderPath(Environment.SpecialFolder.MyDocuments) + "\\Terminal-" + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".txt"); } @@ -79,13 +84,22 @@ public void Connect() { if (!_RunRxThread) { - var Session = new RFD.RFD900.TSession(SikRadio.Config.comPort); - Session.PutIntoATCommandMode(); - Session.Dispose(); - - _RunRxThread = true; - _RxThread = new Thread(RxWorker); - _RxThread.Start(); + if (RFDLib.Utils.Retry(() => + { + var Session = new RFD.RFD900.TSession(SikRadio.Config.comPort, MainV2.comPort.BaseStream.BaudRate); + var Result = Session.PutIntoATCommandMode() == RFD.RFD900.TSession.TMode.AT_COMMAND; + Session.Dispose(); + return Result; + }, 3)) + { + _RunRxThread = true; + _RxThread = new Thread(RxWorker); + _RxThread.Start(); + } + else + { + MissionPlanner.MsgBox.CustomMessageBox.Show("Failed to enter AT command mode."); + } } } @@ -287,5 +301,13 @@ private void TXT_terminal_KeyPress(object sender, KeyPressEventArgs e) cmd.Append(e.KeyChar); } } + + public string Header + { + get + { + return "Terminal"; + } + } } } \ No newline at end of file diff --git a/Swarm/Formation.cs b/Swarm/Formation.cs index 3e08a7572d..2628291323 100644 --- a/Swarm/Formation.cs +++ b/Swarm/Formation.cs @@ -191,7 +191,7 @@ public override void SendCommand() if (true) { - var leaderturnrad = Leader.cs.radius; + var leaderturnrad = CurrentState.fromDistDisplayUnit(Leader.cs.radius); var mavturnradius = leaderturnrad - x; { diff --git a/build - Clean.bat b/build - Clean.bat index 7746652e16..d19d5116ec 100644 --- a/build - Clean.bat +++ b/build - Clean.bat @@ -1,4 +1,4 @@ -set PATH=%PATH%;C:\Program Files (x86)\Microsoft Visual Studio\2019\Preview\MSBuild\Current\Bin;C:\Program Files (x86)\Microsoft Visual Studio\Preview\Community\MSBuild\15.0\Bin;C:\Program Files (x86)\Microsoft Visual Studio\2017\Community\MSBuild\15.0\Bin +set PATH=%PATH%;C:\Program Files\Microsoft Visual Studio\2022\Community\Msbuild\Current\Bin;C:\Program Files (x86)\Microsoft Visual Studio\2019\Preview\MSBuild\Current\Bin;C:\Program Files (x86)\Microsoft Visual Studio\Preview\Community\MSBuild\15.0\Bin;C:\Program Files (x86)\Microsoft Visual Studio\2017\Community\MSBuild\15.0\Bin "MSBuild.exe" MissionPlanner.sln /m /p:Configuration=Debug /verbosity:d /t:Clean "MSBuild.exe" MissionPlanner.sln /m /p:Configuration=Release /verbosity:d /t:Clean diff --git a/build - debug.bat b/build - debug.bat new file mode 100644 index 0000000000..073e05a559 --- /dev/null +++ b/build - debug.bat @@ -0,0 +1,10 @@ + +set PATH=%PATH%;C:\Program Files\Microsoft Visual Studio\2022\Community\Msbuild\Current\Bin;C:\Program Files (x86)\Microsoft Visual Studio\2019\Preview\MSBuild\Current\Bin;C:\Program Files (x86)\Microsoft Visual Studio\Preview\Community\MSBuild\15.0\Bin;C:\Program Files (x86)\Microsoft Visual Studio\2017\Community\MSBuild\15.0\Bin + +del bin\release\MissionPlannerBeta.zip + +.nuget\nuget.exe restore MissionPlanner.sln + +MSBuild.exe MissionPlanner.sln /restore /m /p:Configuration=Debug /verbosity:n + +pause \ No newline at end of file diff --git a/mavcmd.xml b/mavcmd.xml index 1977720528..3aa129131e 100644 --- a/mavcmd.xml +++ b/mavcmd.xml @@ -193,7 +193,7 @@ - Type + Type (0:horiz,2:up,3:down) Speed m/s diff --git a/temp.Designer.cs b/temp.Designer.cs index fa8da2fd04..6c2550f4b3 100644 --- a/temp.Designer.cs +++ b/temp.Designer.cs @@ -30,6 +30,8 @@ private void InitializeComponent() { System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(temp)); this.tableLayoutPanel1 = new System.Windows.Forms.TableLayoutPanel(); + this.BUT_forcecal_accel = new MissionPlanner.Controls.MyButton(); + this.BUT_forcecal_mag = new MissionPlanner.Controls.MyButton(); this.but_apjtool = new MissionPlanner.Controls.MyButton(); this.BUT_CoT = new MissionPlanner.Controls.MyButton(); this.but_proximity = new MissionPlanner.Controls.MyButton(); @@ -145,13 +147,11 @@ private void InitializeComponent() this.label12 = new System.Windows.Forms.Label(); this.but_ManageCMDList = new MissionPlanner.Controls.MyButton(); this.label28 = new System.Windows.Forms.Label(); - this.controlSensorsStatus1 = new MissionPlanner.Controls.ControlSensorsStatus(); this.but_dfumode = new MissionPlanner.Controls.MyButton(); this.label56 = new System.Windows.Forms.Label(); - this.BUT_forcecal_mag = new MissionPlanner.Controls.MyButton(); - this.BUT_forcecal_accel = new MissionPlanner.Controls.MyButton(); this.label57 = new System.Windows.Forms.Label(); this.label58 = new System.Windows.Forms.Label(); + this.controlSensorsStatus1 = new MissionPlanner.Controls.ControlSensorsStatus(); this.tableLayoutPanel1.SuspendLayout(); this.SuspendLayout(); // @@ -282,10 +282,27 @@ private void InitializeComponent() this.tableLayoutPanel1.Controls.Add(this.label58, 1, 31); this.tableLayoutPanel1.Name = "tableLayoutPanel1"; // + // BUT_forcecal_accel + // + resources.ApplyResources(this.BUT_forcecal_accel, "BUT_forcecal_accel"); + this.BUT_forcecal_accel.Name = "BUT_forcecal_accel"; + this.BUT_forcecal_accel.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); + this.BUT_forcecal_accel.UseVisualStyleBackColor = true; + this.BUT_forcecal_accel.Click += new System.EventHandler(this.BUT_forcecal_accel_Click); + // + // BUT_forcecal_mag + // + resources.ApplyResources(this.BUT_forcecal_mag, "BUT_forcecal_mag"); + this.BUT_forcecal_mag.Name = "BUT_forcecal_mag"; + this.BUT_forcecal_mag.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); + this.BUT_forcecal_mag.UseVisualStyleBackColor = true; + this.BUT_forcecal_mag.Click += new System.EventHandler(this.BUT_forcecal_mag_Click); + // // but_apjtool // resources.ApplyResources(this.but_apjtool, "but_apjtool"); this.but_apjtool.Name = "but_apjtool"; + this.but_apjtool.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_apjtool.UseVisualStyleBackColor = true; this.but_apjtool.Click += new System.EventHandler(this.but_signfw_Click); // @@ -293,6 +310,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_CoT, "BUT_CoT"); this.BUT_CoT.Name = "BUT_CoT"; + this.BUT_CoT.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_CoT.UseVisualStyleBackColor = true; this.BUT_CoT.Click += new System.EventHandler(this.BUT_CoT_Click); // @@ -300,6 +318,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_proximity, "but_proximity"); this.but_proximity.Name = "but_proximity"; + this.but_proximity.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_proximity.UseVisualStyleBackColor = true; this.but_proximity.Click += new System.EventHandler(this.but_proximity_Click); // @@ -307,6 +326,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_followswarm, "but_followswarm"); this.but_followswarm.Name = "but_followswarm"; + this.but_followswarm.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_followswarm.UseVisualStyleBackColor = true; this.but_followswarm.Click += new System.EventHandler(this.but_followswarm_Click); // @@ -319,6 +339,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_lockup, "but_lockup"); this.but_lockup.Name = "but_lockup"; + this.but_lockup.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_lockup.UseVisualStyleBackColor = true; this.but_lockup.Click += new System.EventHandler(this.but_lockup_Click); // @@ -326,6 +347,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_td, "but_td"); this.but_td.Name = "but_td"; + this.but_td.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_td.UseVisualStyleBackColor = true; this.but_td.Click += new System.EventHandler(this.but_td_Click); // @@ -333,6 +355,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_gpsinj, "but_gpsinj"); this.but_gpsinj.Name = "but_gpsinj"; + this.but_gpsinj.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_gpsinj.UseVisualStyleBackColor = true; this.but_gpsinj.Click += new System.EventHandler(this.but_gpsinj_Click); // @@ -340,6 +363,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_dem, "but_dem"); this.but_dem.Name = "but_dem"; + this.but_dem.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_dem.UseVisualStyleBackColor = true; this.but_dem.Click += new System.EventHandler(this.but_dem_Click); // @@ -347,6 +371,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_magfit2, "BUT_magfit2"); this.BUT_magfit2.Name = "BUT_magfit2"; + this.BUT_magfit2.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_magfit2.UseVisualStyleBackColor = true; this.BUT_magfit2.Click += new System.EventHandler(this.BUT_magfit2_Click); // @@ -354,6 +379,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_GDAL, "but_GDAL"); this.but_GDAL.Name = "but_GDAL"; + this.but_GDAL.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_GDAL.UseVisualStyleBackColor = true; this.but_GDAL.Click += new System.EventHandler(this.but_GDAL_Click); // @@ -361,6 +387,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_sortlogs, "but_sortlogs"); this.but_sortlogs.Name = "but_sortlogs"; + this.but_sortlogs.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_sortlogs.UseVisualStyleBackColor = true; this.but_sortlogs.Click += new System.EventHandler(this.but_sortlogs_Click); // @@ -368,6 +395,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_optflowcalib, "but_optflowcalib"); this.but_optflowcalib.Name = "but_optflowcalib"; + this.but_optflowcalib.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_optflowcalib.UseVisualStyleBackColor = true; this.but_optflowcalib.Click += new System.EventHandler(this.but_optflowcalib_Click); // @@ -375,6 +403,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_logdlscp, "but_logdlscp"); this.but_logdlscp.Name = "but_logdlscp"; + this.but_logdlscp.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_logdlscp.UseVisualStyleBackColor = true; this.but_logdlscp.Click += new System.EventHandler(this.but_logdlscp_Click); // @@ -382,6 +411,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_signkey, "but_signkey"); this.but_signkey.Name = "but_signkey"; + this.but_signkey.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_signkey.UseVisualStyleBackColor = true; this.but_signkey.Click += new System.EventHandler(this.but_signkey_Click); // @@ -389,6 +419,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_acbarohight, "but_acbarohight"); this.but_acbarohight.Name = "but_acbarohight"; + this.but_acbarohight.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_acbarohight.UseVisualStyleBackColor = true; this.but_acbarohight.Click += new System.EventHandler(this.but_acbarohight_Click); // @@ -396,6 +427,7 @@ private void InitializeComponent() // resources.ApplyResources(this.myButton1, "myButton1"); this.myButton1.Name = "myButton1"; + this.myButton1.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.myButton1.UseVisualStyleBackColor = true; this.myButton1.Click += new System.EventHandler(this.myButton1_Click_2); // @@ -403,6 +435,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_driverclean, "but_driverclean"); this.but_driverclean.Name = "but_driverclean"; + this.but_driverclean.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_driverclean.UseVisualStyleBackColor = true; this.but_driverclean.Click += new System.EventHandler(this.BUT_driverclean_Click); // @@ -410,6 +443,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_agemapdata, "but_agemapdata"); this.but_agemapdata.Name = "but_agemapdata"; + this.but_agemapdata.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_agemapdata.UseVisualStyleBackColor = true; this.but_agemapdata.Click += new System.EventHandler(this.but_agemapdata_Click); // @@ -417,6 +451,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_packetbytes, "but_packetbytes"); this.but_packetbytes.Name = "but_packetbytes"; + this.but_packetbytes.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_packetbytes.UseVisualStyleBackColor = true; this.but_packetbytes.Click += new System.EventHandler(this.but_packetbytes_Click); // @@ -424,6 +459,7 @@ private void InitializeComponent() // resources.ApplyResources(this.myButton_vlc, "myButton_vlc"); this.myButton_vlc.Name = "myButton_vlc"; + this.myButton_vlc.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.myButton_vlc.UseVisualStyleBackColor = true; this.myButton_vlc.Click += new System.EventHandler(this.myButton_vlc_Click); // @@ -436,6 +472,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_trimble, "but_trimble"); this.but_trimble.Name = "but_trimble"; + this.but_trimble.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_trimble.UseVisualStyleBackColor = true; this.but_trimble.Click += new System.EventHandler(this.but_trimble_Click); // @@ -443,6 +480,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_hwids, "but_hwids"); this.but_hwids.Name = "but_hwids"; + this.but_hwids.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_hwids.UseVisualStyleBackColor = true; this.but_hwids.Click += new System.EventHandler(this.but_hwids_Click); // @@ -450,6 +488,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_QNH, "BUT_QNH"); this.BUT_QNH.Name = "BUT_QNH"; + this.BUT_QNH.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_QNH.UseVisualStyleBackColor = true; this.BUT_QNH.Click += new System.EventHandler(this.BUT_QNH_Click); // @@ -457,6 +496,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_reboot, "but_reboot"); this.but_reboot.Name = "but_reboot"; + this.but_reboot.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_reboot.UseVisualStyleBackColor = true; this.but_reboot.Click += new System.EventHandler(this.but_reboot_Click); // @@ -464,6 +504,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_3dmap, "but_3dmap"); this.but_3dmap.Name = "but_3dmap"; + this.but_3dmap.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_3dmap.UseVisualStyleBackColor = true; this.but_3dmap.Click += new System.EventHandler(this.but_3dmap_Click); // @@ -471,6 +512,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_messageinterval, "but_messageinterval"); this.but_messageinterval.Name = "but_messageinterval"; + this.but_messageinterval.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_messageinterval.UseVisualStyleBackColor = true; this.but_messageinterval.Click += new System.EventHandler(this.but_messageinterval_Click); // @@ -478,6 +520,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_blupdate, "but_blupdate"); this.but_blupdate.Name = "but_blupdate"; + this.but_blupdate.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_blupdate.UseVisualStyleBackColor = true; this.but_blupdate.Click += new System.EventHandler(this.but_blupdate_Click); // @@ -485,6 +528,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_fft, "BUT_fft"); this.BUT_fft.Name = "BUT_fft"; + this.BUT_fft.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_fft.UseVisualStyleBackColor = true; this.BUT_fft.Click += new System.EventHandler(this.BUT_fft_Click); // @@ -492,6 +536,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_disablearmswitch, "but_disablearmswitch"); this.but_disablearmswitch.Name = "but_disablearmswitch"; + this.but_disablearmswitch.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_disablearmswitch.UseVisualStyleBackColor = true; this.but_disablearmswitch.Click += new System.EventHandler(this.but_disablearmswitch_Click); // @@ -499,6 +544,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_paramrestore, "but_paramrestore"); this.but_paramrestore.Name = "but_paramrestore"; + this.but_paramrestore.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_paramrestore.UseVisualStyleBackColor = true; this.but_paramrestore.Click += new System.EventHandler(this.but_paramrestore_Click); // @@ -506,6 +552,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_mavinspector, "but_mavinspector"); this.but_mavinspector.Name = "but_mavinspector"; + this.but_mavinspector.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_mavinspector.UseVisualStyleBackColor = true; this.but_mavinspector.Click += new System.EventHandler(this.but_mavinspector_Click); // @@ -513,6 +560,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_sitl_comb, "but_sitl_comb"); this.but_sitl_comb.Name = "but_sitl_comb"; + this.but_sitl_comb.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_sitl_comb.UseVisualStyleBackColor = true; this.but_sitl_comb.Click += new System.EventHandler(this.but_sitl_comb_Click); // @@ -520,6 +568,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_anonlog, "but_anonlog"); this.but_anonlog.Name = "but_anonlog"; + this.but_anonlog.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_anonlog.UseVisualStyleBackColor = true; this.but_anonlog.Click += new System.EventHandler(this.but_anonlog_Click); // @@ -527,6 +576,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_dashware, "but_dashware"); this.but_dashware.Name = "but_dashware"; + this.but_dashware.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_dashware.UseVisualStyleBackColor = true; this.but_dashware.Click += new System.EventHandler(this.but_dashware_Click); // @@ -574,6 +624,7 @@ private void InitializeComponent() // resources.ApplyResources(this.butlogindex, "butlogindex"); this.butlogindex.Name = "butlogindex"; + this.butlogindex.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.butlogindex.UseVisualStyleBackColor = true; this.butlogindex.Click += new System.EventHandler(this.butlogindex_Click); // @@ -581,12 +632,14 @@ private void InitializeComponent() // resources.ApplyResources(this.but_armandtakeoff, "but_armandtakeoff"); this.but_armandtakeoff.Name = "but_armandtakeoff"; + this.but_armandtakeoff.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_armandtakeoff.Click += new System.EventHandler(this.but_armandtakeoff_Click); // // but_maplogs // resources.ApplyResources(this.but_maplogs, "but_maplogs"); this.but_maplogs.Name = "but_maplogs"; + this.but_maplogs.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_maplogs.UseVisualStyleBackColor = true; this.but_maplogs.Click += new System.EventHandler(this.but_maplogs_Click); // @@ -599,6 +652,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_gimbaltest, "but_gimbaltest"); this.but_gimbaltest.Name = "but_gimbaltest"; + this.but_gimbaltest.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_gimbaltest.UseVisualStyleBackColor = true; this.but_gimbaltest.Click += new System.EventHandler(this.but_gimbaltest_Click); // @@ -606,6 +660,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_structtest, "but_structtest"); this.but_structtest.Name = "but_structtest"; + this.but_structtest.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_structtest.UseVisualStyleBackColor = true; this.but_structtest.Click += new System.EventHandler(this.but_structtest_Click); // @@ -643,6 +698,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_clearcustommaps, "BUT_clearcustommaps"); this.BUT_clearcustommaps.Name = "BUT_clearcustommaps"; + this.BUT_clearcustommaps.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_clearcustommaps.UseVisualStyleBackColor = true; this.BUT_clearcustommaps.Click += new System.EventHandler(this.BUT_clearcustommaps_Click); // @@ -650,6 +706,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_getfw, "but_getfw"); this.but_getfw.Name = "but_getfw"; + this.but_getfw.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_getfw.UseVisualStyleBackColor = true; this.but_getfw.Click += new System.EventHandler(this.but_getfw_Click); // @@ -657,6 +714,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_geinjection, "BUT_geinjection"); this.BUT_geinjection.Name = "BUT_geinjection"; + this.BUT_geinjection.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_geinjection.UseVisualStyleBackColor = true; this.BUT_geinjection.Click += new System.EventHandler(this.BUT_geinjection_Click); // @@ -674,6 +732,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_sorttlogs, "BUT_sorttlogs"); this.BUT_sorttlogs.Name = "BUT_sorttlogs"; + this.BUT_sorttlogs.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_sorttlogs.UseVisualStyleBackColor = true; this.BUT_sorttlogs.Click += new System.EventHandler(this.BUT_sorttlogs_Click); // @@ -706,6 +765,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_outputMavlink, "BUT_outputMavlink"); this.BUT_outputMavlink.Name = "BUT_outputMavlink"; + this.BUT_outputMavlink.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_outputMavlink.UseVisualStyleBackColor = true; this.BUT_outputMavlink.Click += new System.EventHandler(this.BUT_outputMavlink_Click); // @@ -713,6 +773,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_outputMD, "BUT_outputMD"); this.BUT_outputMD.Name = "BUT_outputMD"; + this.BUT_outputMD.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_outputMD.UseVisualStyleBackColor = true; this.BUT_outputMD.Click += new System.EventHandler(this.myButton1_Click); // @@ -720,6 +781,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_outputnmea, "BUT_outputnmea"); this.BUT_outputnmea.Name = "BUT_outputnmea"; + this.BUT_outputnmea.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_outputnmea.UseVisualStyleBackColor = true; this.BUT_outputnmea.Click += new System.EventHandler(this.BUT_outputnmea_Click); // @@ -727,12 +789,14 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_georefimage, "BUT_georefimage"); this.BUT_georefimage.Name = "BUT_georefimage"; + this.BUT_georefimage.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_georefimage.Click += new System.EventHandler(this.BUT_georefimage_Click); // // button3 // resources.ApplyResources(this.button3, "button3"); this.button3.Name = "button3"; + this.button3.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.button3.UseVisualStyleBackColor = true; this.button3.Click += new System.EventHandler(this.button3_Click); // @@ -740,6 +804,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_lang_edit, "BUT_lang_edit"); this.BUT_lang_edit.Name = "BUT_lang_edit"; + this.BUT_lang_edit.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_lang_edit.UseVisualStyleBackColor = true; this.BUT_lang_edit.Click += new System.EventHandler(this.BUT_lang_edit_Click); // @@ -747,6 +812,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_follow_me, "BUT_follow_me"); this.BUT_follow_me.Name = "BUT_follow_me"; + this.BUT_follow_me.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_follow_me.UseVisualStyleBackColor = true; this.BUT_follow_me.Click += new System.EventHandler(this.BUT_follow_me_Click); // @@ -754,6 +820,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_paramgen, "BUT_paramgen"); this.BUT_paramgen.Name = "BUT_paramgen"; + this.BUT_paramgen.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_paramgen.UseVisualStyleBackColor = true; this.BUT_paramgen.Click += new System.EventHandler(this.BUT_paramgen_Click); // @@ -761,6 +828,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_osdvideo, "but_osdvideo"); this.but_osdvideo.Name = "but_osdvideo"; + this.but_osdvideo.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_osdvideo.UseVisualStyleBackColor = true; this.but_osdvideo.Click += new System.EventHandler(this.but_osdvideo_Click); // @@ -768,6 +836,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_movingbase, "BUT_movingbase"); this.BUT_movingbase.Name = "BUT_movingbase"; + this.BUT_movingbase.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_movingbase.UseVisualStyleBackColor = true; this.BUT_movingbase.Click += new System.EventHandler(this.BUT_movingbase_Click); // @@ -775,6 +844,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_shptopoly, "BUT_shptopoly"); this.BUT_shptopoly.Name = "BUT_shptopoly"; + this.BUT_shptopoly.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_shptopoly.UseVisualStyleBackColor = true; this.BUT_shptopoly.Click += new System.EventHandler(this.BUT_shptopoly_Click); // @@ -782,6 +852,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_swarm, "BUT_swarm"); this.BUT_swarm.Name = "BUT_swarm"; + this.BUT_swarm.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_swarm.UseVisualStyleBackColor = true; this.BUT_swarm.Click += new System.EventHandler(this.BUT_swarm_Click); // @@ -789,6 +860,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_followleader, "BUT_followleader"); this.BUT_followleader.Name = "BUT_followleader"; + this.BUT_followleader.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_followleader.UseVisualStyleBackColor = true; this.BUT_followleader.Click += new System.EventHandler(this.BUT_followleader_Click); // @@ -801,6 +873,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_mavserialport, "but_mavserialport"); this.but_mavserialport.Name = "but_mavserialport"; + this.but_mavserialport.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_mavserialport.UseVisualStyleBackColor = true; this.but_mavserialport.Click += new System.EventHandler(this.but_mavserialport_Click); // @@ -808,6 +881,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_hexmavlink, "but_hexmavlink"); this.but_hexmavlink.Name = "but_hexmavlink"; + this.but_hexmavlink.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_hexmavlink.UseVisualStyleBackColor = true; this.but_hexmavlink.Click += new System.EventHandler(this.but_hexmavlink_Click); // @@ -955,6 +1029,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_remotedflogger, "but_remotedflogger"); this.but_remotedflogger.Name = "but_remotedflogger"; + this.but_remotedflogger.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_remotedflogger.UseVisualStyleBackColor = true; this.but_remotedflogger.Click += new System.EventHandler(this.but_remotedflogger_Click); // @@ -967,6 +1042,7 @@ private void InitializeComponent() // resources.ApplyResources(this.but_ManageCMDList, "but_ManageCMDList"); this.but_ManageCMDList.Name = "but_ManageCMDList"; + this.but_ManageCMDList.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_ManageCMDList.UseVisualStyleBackColor = true; this.but_ManageCMDList.Click += new System.EventHandler(this.but_ManageCMDList_Click); // @@ -975,15 +1051,11 @@ private void InitializeComponent() resources.ApplyResources(this.label28, "label28"); this.label28.Name = "label28"; // - // controlSensorsStatus1 - // - resources.ApplyResources(this.controlSensorsStatus1, "controlSensorsStatus1"); - this.controlSensorsStatus1.Name = "controlSensorsStatus1"; - // // but_dfumode // resources.ApplyResources(this.but_dfumode, "but_dfumode"); this.but_dfumode.Name = "but_dfumode"; + this.but_dfumode.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.but_dfumode.UseVisualStyleBackColor = true; this.but_dfumode.Click += new System.EventHandler(this.but_dfumode_Click); // @@ -992,21 +1064,6 @@ private void InitializeComponent() resources.ApplyResources(this.label56, "label56"); this.label56.Name = "label56"; // - // - // BUT_forcecal_mag - // - resources.ApplyResources(this.BUT_forcecal_mag, "BUT_forcecal_mag"); - this.BUT_forcecal_mag.Name = "BUT_forcecal_mag"; - this.BUT_forcecal_mag.UseVisualStyleBackColor = true; - this.BUT_forcecal_mag.Click += new System.EventHandler(this.BUT_forcecal_mag_Click); - // - // BUT_forcecal_accel - // - resources.ApplyResources(this.BUT_forcecal_accel, "BUT_forcecal_accel"); - this.BUT_forcecal_accel.Name = "BUT_forcecal_accel"; - this.BUT_forcecal_accel.UseVisualStyleBackColor = true; - this.BUT_forcecal_accel.Click += new System.EventHandler(this.BUT_forcecal_accel_Click); - // // label57 // resources.ApplyResources(this.label57, "label57"); @@ -1017,6 +1074,11 @@ private void InitializeComponent() resources.ApplyResources(this.label58, "label58"); this.label58.Name = "label58"; // + // controlSensorsStatus1 + // + resources.ApplyResources(this.controlSensorsStatus1, "controlSensorsStatus1"); + this.controlSensorsStatus1.Name = "controlSensorsStatus1"; + // // temp // resources.ApplyResources(this, "$this"); diff --git a/temp.cs b/temp.cs index 9576ae13e8..0283f4a2bf 100644 --- a/temp.cs +++ b/temp.cs @@ -719,101 +719,18 @@ private void but_agemapdata_Click(object sender, EventArgs e) private void myButton1_Click_2(object sender, EventArgs e) { - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduCopter-2.8.1/ArduCopter/Parameters.pde" - , "ArduCopter2.8.1.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduCopter-2.9.1/ArduCopter/Parameters.pde" - , "ArduCopter2.9.1.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduCopter-3.0/ArduCopter/Parameters.pde" - , "ArduCopter3.0.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduCopter-3.1.5/ArduCopter/Parameters.pde" - , "ArduCopter3.1.5.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduCopter-3.2.1/ArduCopter/Parameters.pde" - , "ArduCopter3.2.1.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.3.2/ArduCopter/Parameters.cpp" - , "ArduCopter3.3.2.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.3/ArduCopter/Parameters.cpp" - , "ArduCopter3.3.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.4/ArduCopter/Parameters.cpp" - , "ArduCopter3.4.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.4.6/ArduCopter/Parameters.cpp" - , "ArduCopter3.4.6.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.5.0/ArduCopter/Parameters.cpp" - , "ArduCopter3.5.0.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.5.2/ArduCopter/Parameters.cpp" - , "ArduCopter3.5.2.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/Copter-3.5.4/ArduCopter/Parameters.cpp" - , "ArduCopter3.5.4.xml"); - - - - // plane - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.8.3/ArduPlane/Parameters.cpp" - , "ArduPlane3.8.3.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.7.1/ArduPlane/Parameters.cpp" - , "ArduPlane3.7.1.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.7.0/ArduPlane/Parameters.cpp" - , "ArduPlane3.7.0.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.6.0/ArduPlane/Parameters.cpp" - , "ArduPlane3.6.0.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.5.2/ArduPlane/Parameters.cpp" - , "ArduPlane3.5.2.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.3.0/ArduPlane/Parameters.pde" - , "ArduPlane3.3.0.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.2.2/ArduPlane/Parameters.pde" - , "ArduPlane3.2.2.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.1.0/ArduPlane/Parameters.pde" - , "ArduPlane3.1.0.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-3.0.3/ArduPlane/Parameters.pde" - , "ArduPlane3.0.3.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-2.78b/ArduPlane/Parameters.pde" - , "ArduPlane2.78b.xml"); - - ParameterMetaDataParser.GetParameterInformation( - "https://raw.githubusercontent.com/ArduPilot/ardupilot/ArduPlane-2.75/ArduPlane/Parameters.pde" - , "ArduPlane2.75.xml"); + + OpenFileDialog openFileDialog1 = new OpenFileDialog(); + openFileDialog1.Filter = "Log Files|*.log;*.bin;*.BIN;*.LOG"; + openFileDialog1.FilterIndex = 2; + openFileDialog1.Multiselect = true; + openFileDialog1.InitialDirectory = Settings.Instance.LogDir; + if (openFileDialog1.ShowDialog() == DialogResult.OK) + { + int a = 10; + InputBox.Show("How Many", "Enter how many pieces to split into", ref a); + new DFLogBuffer(openFileDialog1.FileName).SplitLog(a); + } } private void but_signkey_Click(object sender, EventArgs e) diff --git a/temp.resx b/temp.resx index d663b5c60d..7822986588 100644 --- a/temp.resx +++ b/temp.resx @@ -310,7 +310,7 @@ 557, 475 - 185, 16 + 149, 13 92 @@ -676,7 +676,7 @@ 73 - Param gen cust + Split DFLog myButton1 @@ -820,7 +820,7 @@ 134, 399 - 190, 16 + 153, 13 98 @@ -1270,7 +1270,7 @@ 134, 475 - 80, 16 + 64, 13 72 @@ -1300,7 +1300,7 @@ 134, 456 - 216, 16 + 171, 13 71 @@ -1330,7 +1330,7 @@ 134, 437 - 170, 16 + 136, 13 70 @@ -1360,7 +1360,7 @@ 134, 418 - 136, 16 + 111, 13 69 @@ -1390,7 +1390,7 @@ 134, 380 - 173, 16 + 140, 13 67 @@ -1420,7 +1420,7 @@ 134, 361 - 133, 16 + 105, 13 66 @@ -1450,7 +1450,7 @@ 134, 342 - 165, 16 + 130, 13 65 @@ -1480,7 +1480,7 @@ 134, 323 - 151, 16 + 123, 13 64 @@ -1600,7 +1600,7 @@ 134, 304 - 211, 19 + 214, 13 63 @@ -1690,7 +1690,7 @@ 134, 266 - 256, 19 + 252, 13 61 @@ -1720,7 +1720,7 @@ 134, 247 - 146, 16 + 117, 13 60 @@ -1750,7 +1750,7 @@ 134, 228 - 159, 16 + 128, 13 59 @@ -1780,7 +1780,7 @@ 134, 190 - 193, 16 + 156, 13 57 @@ -1810,7 +1810,7 @@ 134, 171 - 231, 19 + 226, 19 56 @@ -1840,7 +1840,7 @@ 134, 152 - 253, 16 + 202, 13 55 @@ -1960,7 +1960,7 @@ 134, 133 - 165, 16 + 131, 13 54 @@ -1990,7 +1990,7 @@ 134, 114 - 254, 16 + 201, 13 53 @@ -2050,7 +2050,7 @@ 134, 95 - 258, 16 + 203, 13 52 @@ -2080,7 +2080,7 @@ 134, 76 - 237, 19 + 221, 13 51 @@ -2110,7 +2110,7 @@ 134, 57 - 200, 16 + 163, 13 50 @@ -2140,7 +2140,7 @@ 134, 38 - 176, 16 + 141, 13 49 @@ -2170,7 +2170,7 @@ 134, 19 - 186, 16 + 149, 13 48 @@ -2590,7 +2590,7 @@ 134, 0 - 143, 16 + 115, 13 47 @@ -2680,7 +2680,7 @@ 134, 532 - 160, 16 + 128, 13 106 @@ -2710,7 +2710,7 @@ 134, 494 - 263, 19 + 263, 13 108 @@ -2740,7 +2740,7 @@ 557, 19 - 150, 16 + 117, 13 109 @@ -2770,7 +2770,7 @@ 557, 38 - 175, 16 + 142, 13 110 @@ -2800,7 +2800,7 @@ 557, 57 - 208, 19 + 212, 13 111 @@ -2830,7 +2830,7 @@ 557, 76 - 207, 19 + 218, 13 112 @@ -2860,7 +2860,7 @@ 557, 95 - 139, 16 + 111, 13 113 @@ -2890,7 +2890,7 @@ 557, 114 - 94, 16 + 76, 13 114 @@ -2920,7 +2920,7 @@ 557, 133 - 236, 19 + 196, 13 115 @@ -2950,7 +2950,7 @@ 557, 152 - 209, 16 + 169, 13 116 @@ -2980,7 +2980,7 @@ 557, 171 - 172, 16 + 137, 13 117 @@ -3010,7 +3010,7 @@ 557, 190 - 176, 16 + 144, 13 118 @@ -3040,7 +3040,7 @@ 557, 209 - 233, 19 + 222, 19 119 @@ -3070,7 +3070,7 @@ 557, 228 - 217, 16 + 172, 13 120 @@ -3100,7 +3100,7 @@ 557, 247 - 216, 19 + 200, 13 121 @@ -3130,7 +3130,7 @@ 557, 266 - 209, 19 + 196, 13 122 @@ -3160,7 +3160,7 @@ 557, 304 - 19, 16 + 19, 13 123 @@ -3190,7 +3190,7 @@ 557, 323 - 19, 16 + 19, 13 124 @@ -3220,7 +3220,7 @@ 557, 342 - 16, 16 + 16, 13 125 @@ -3250,7 +3250,7 @@ 557, 361 - 121, 16 + 98, 13 126 @@ -3280,7 +3280,7 @@ 557, 380 - 89, 16 + 74, 13 127 @@ -3310,7 +3310,7 @@ 557, 399 - 51, 16 + 41, 13 128 @@ -3340,7 +3340,7 @@ 557, 418 - 214, 19 + 212, 19 129 @@ -3370,7 +3370,7 @@ 557, 437 - 233, 16 + 184, 13 130 @@ -3400,13 +3400,13 @@ 557, 456 - 168, 16 + 113, 13 131 - generate aged param data + split dflog into x pieces label52 @@ -3430,7 +3430,7 @@ 557, 494 - 158, 16 + 129, 13 132 @@ -3460,7 +3460,7 @@ 557, 513 - 141, 16 + 111, 13 133 @@ -3490,7 +3490,7 @@ 557, 532 - 77, 16 + 61, 13 134 @@ -3544,7 +3544,7 @@ 134, 551 - 157, 16 + 126, 13 137 @@ -3598,7 +3598,7 @@ 557, 551 - 204, 16 + 161, 13 139 @@ -3649,7 +3649,7 @@ 557, 570 - 73, 16 + 59, 13 141 @@ -3679,7 +3679,7 @@ 134, 570 - 239, 16 + 190, 13 144 @@ -3709,7 +3709,7 @@ 134, 589 - 233, 16 + 184, 13 145 @@ -3772,7 +3772,7 @@ controlSensorsStatus1 - MissionPlanner.Controls.ControlSensorsStatus, MissionPlanner, Version=1.3.8446.38353, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.ControlSensorsStatus, MissionPlanner, Version=1.3.8820.14861, Culture=neutral, PublicKeyToken=null $this @@ -3790,7 +3790,7 @@ True - 1027, 628 + 1044, 628 temp