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}
+ net472Library
- 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.xmlloweheiser.xmlcubepilot.xml
+ csAirLink.xml2
@@ -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 compensatedFlow in y-sensor direction, angular-speed compensatedOptical flow quality / confidence. 0: bad, 255: maximum quality
@@ -4951,6 +5050,9 @@
True velocity in north direction in earth-fixed NED frameTrue velocity in east direction in earth-fixed NED frameTrue 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 IDComponent IDLow 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 IDComponent IDTimestamp (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 IDComponent IDTimestamp (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 IDComponent IDHigh 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_MESSAGEName 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 outputsServo / 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)