diff --git a/Controls/DevopsUI.cs b/Controls/DevopsUI.cs index 9a4c0b4b49..f0e377e43e 100644 --- a/Controls/DevopsUI.cs +++ b/Controls/DevopsUI.cs @@ -20,12 +20,15 @@ public DevopsUI() private void but_doit_Click(object sender, EventArgs e) { var buffer = new byte[Convert.ToByte(num_count.Text)]; - MainV2.comPort.device_op(Convert.ToByte(num_sysid.Text), Convert.ToByte(num_compid.Text), out buffer, + var result = MainV2.comPort.device_op(Convert.ToByte(num_sysid.Text), Convert.ToByte(num_compid.Text), out buffer, dom_bustype.Text == "SPI" ? MAVLink.DEVICE_OP_BUSTYPE.SPI : MAVLink.DEVICE_OP_BUSTYPE.I2C, txt_spiname.Text, Convert.ToByte(num_busno.Text), Convert.ToByte(num_address.Text), Convert.ToByte(num_regstart.Text), Convert.ToByte(num_count.Text)); - textBox1.AppendText(buffer.Select(a => a.ToString("X2")).Aggregate((a, b) => a + b) + "\r\n"); + if (buffer.Length > 0) + textBox1.AppendText(buffer.Select(a => a.ToString("X2")).Aggregate((a, b) => a + b) + "\r\n"); + else + textBox1.AppendText("No Responce - " + result + "\r\n"); } private void dom_bustype_SelectedItemChanged(object sender, EventArgs e) diff --git a/Controls/OpenGLtest2.cs b/Controls/OpenGLtest2.cs index 28f7b9edf9..a031a4e11d 100644 --- a/Controls/OpenGLtest2.cs +++ b/Controls/OpenGLtest2.cs @@ -256,7 +256,7 @@ static int generateTexture(Bitmap image) } static void ConvertColorSpace(BitmapData _data) - { + { // bgra to rgba var x = 0; var y = 0; var width = _data.Width; var height = _data.Height; for (y = 0; y < height; y++) @@ -295,7 +295,7 @@ static int CreateTexture(BitmapData data) } else { - // No, it's not a power of 2. Turn of mips and set wrapping to clamp to edge + // No, it's not a power of 2. Turn of mips and set wrapping to clamp to edge GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear); } return texture; @@ -310,7 +310,7 @@ static int FloorPowerOf2(int value) { var ans = Math.Log(value, 2); - return (int)Math.Pow(2, Math.Floor(ans)); + return (int)Math.Pow(2, Math.Floor(ans)); } [MethodImpl(MethodImplOptions.AggressiveInlining)] @@ -519,7 +519,7 @@ public void doPaint() /*Console.WriteLine("cam: {0} {1} {2} lookat: {3} {4} {5}", (float) cameraX, (float) cameraY, (float) cameraZ, (float) lookX, (float) lookY, (float) lookZ); - */ + */ modelMatrix = Matrix4.LookAt((float) cameraX, (float) cameraY, (float) cameraZ + 100f * 0, (float) lookX, (float) lookY, (float) lookZ, 0, 0, 1); @@ -539,7 +539,7 @@ public void doPaint() GL.ClearColor(Color.CornflowerBlue); GL.Clear(ClearBufferMask.ColorBufferBit | ClearBufferMask.DepthBufferBit | ClearBufferMask.AccumBufferBit); - + // disable depth during terrain draw GL.Disable(EnableCap.DepthTest); GL.DepthFunc(DepthFunction.Lequal); @@ -642,7 +642,7 @@ public void doPaint() startindex + 1, startindex + 3, startindex + 2 }); - + wpmarker.Draw(projMatrix, modelMatrix); wpmarker.Cleanup(true); @@ -696,7 +696,7 @@ private double[] projectLocation(double[] oldpos) var factor = 0.3; return new double[] { - oldpos[0] * factor + newpos[0] * (1.0 - factor), + oldpos[0] * factor + newpos[0] * (1.0 - factor), oldpos[1] * factor + newpos[1] * (1.0 - factor), oldpos[2] * factor + newpos[2] * (1.0 - factor) }; @@ -758,7 +758,7 @@ private void generateTextures() if (DateTime.Now.Second % 3 == 1) CleanupOldTextures(tileArea); } - + //https://wiki.openstreetmap.org/wiki/Zoom_levels var C = 2 * Math.PI * 6378137.000; // horizontal distance by each tile square @@ -775,6 +775,7 @@ private void generateTextures() stile = C * Math.Cos(_center.Lat) / Math.Pow(2, tilearea.zoom); pxstep = (int)(stile / 45); pxstep = FloorPowerOf2(pxstep); + if (pxstep == int.MinValue) pxstep = 0; if (pxstep == 0) pxstep = 1; foreach (var p in tilearea.points) @@ -879,7 +880,7 @@ private void generateTextures() private void Minimumtile(List tileArea) { - foreach (tileZoomArea tileZoomArea in tileArea.Reverse()) + foreach (tileZoomArea tileZoomArea in tileArea.Reverse()) { //GPoint centerPixel = Provider.Projection.FromLatLngToPixel(center, Zoom); //var centerTileXYLocation = Provider.Projection.FromPixelToTileXY(centerPixel); @@ -1669,9 +1670,9 @@ void main(void) { } GL.UseProgram(_program); - positionSlot = GL.GetAttribLocation(_program, "Position"); - colorSlot = GL.GetAttribLocation(_program, "SourceColor"); - texCoordSlot = GL.GetAttribLocation(_program, "TexCoordIn"); + positionSlot = GL.GetAttribLocation(_program, "Position"); + colorSlot = GL.GetAttribLocation(_program, "SourceColor"); + texCoordSlot = GL.GetAttribLocation(_program, "TexCoordIn"); projectionSlot = GL.GetUniformLocation(_program, "Projection"); modelViewSlot = GL.GetUniformLocation(_program, "ModelView"); textureSlot = GL.GetUniformLocation(_program, "Texture"); @@ -1716,7 +1717,7 @@ public void Cleanup(bool nolock = false) public void Dispose() { Cleanup(); - } + } } [StructLayout(LayoutKind.Sequential, Pack = 1)] diff --git a/Controls/SerialOutputNMEA.cs b/Controls/SerialOutputNMEA.cs index c2480014f2..c6ff3e12b9 100644 --- a/Controls/SerialOutputNMEA.cs +++ b/Controls/SerialOutputNMEA.cs @@ -1,4 +1,5 @@ -using MissionPlanner.Comms; +using GeoidHeightsDotNet; +using MissionPlanner.Comms; using MissionPlanner.Utilities; using System; using System.Globalization; @@ -144,7 +145,8 @@ void mainloop() DateTime.Now.ToUniversalTime(), Math.Abs(lat * 100).ToString("0000.00000", CultureInfo.InvariantCulture), MainV2.comPort.MAV.cs.lat < 0 ? "S" : "N", Math.Abs(lng * 100).ToString("00000.00000", CultureInfo.InvariantCulture), MainV2.comPort.MAV.cs.lng < 0 ? "W" : "E", MainV2.comPort.MAV.cs.gpsstatus >= 3 ? 1 : 0, MainV2.comPort.MAV.cs.satcount, - MainV2.comPort.MAV.cs.gpshdop, MainV2.comPort.MAV.cs.altasl, "M", 0, "M", ""); + MainV2.comPort.MAV.cs.gpshdop, MainV2.comPort.MAV.cs.altasl / CurrentState.multiplieralt, "M", + GeoidHeights.undulation(MainV2.comPort.MAV.cs.lat, MainV2.comPort.MAV.cs.lng).ToString("0.0", CultureInfo.InvariantCulture), "M", ""); string checksum = GetChecksum(line); NmeaStream.WriteLine(line + "*" + checksum+"\r"); diff --git a/Controls/SerialOutputPass.Designer.cs b/Controls/SerialOutputPass.Designer.cs index abba9801cd..2894c0c036 100644 --- a/Controls/SerialOutputPass.Designer.cs +++ b/Controls/SerialOutputPass.Designer.cs @@ -38,6 +38,7 @@ private void InitializeComponent() this.Direction = new System.Windows.Forms.DataGridViewComboBoxColumn(); this.Port = new System.Windows.Forms.DataGridViewTextBoxColumn(); this.Extra = new System.Windows.Forms.DataGridViewTextBoxColumn(); + this.Write = new System.Windows.Forms.DataGridViewCheckBoxColumn(); this.Go = new System.Windows.Forms.DataGridViewButtonColumn(); ((System.ComponentModel.ISupportInitialize)(this.myDataGridView1)).BeginInit(); this.SuspendLayout(); @@ -53,6 +54,7 @@ private void InitializeComponent() // resources.ApplyResources(this.BUT_connect, "BUT_connect"); this.BUT_connect.Name = "BUT_connect"; + this.BUT_connect.TextColorNotEnabled = System.Drawing.Color.FromArgb(((int)(((byte)(64)))), ((int)(((byte)(87)))), ((int)(((byte)(4))))); this.BUT_connect.UseVisualStyleBackColor = true; this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click); // @@ -88,6 +90,7 @@ private void InitializeComponent() this.Direction, this.Port, this.Extra, + this.Write, this.Go}); this.myDataGridView1.Name = "myDataGridView1"; this.myDataGridView1.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.myDataGridView1_CellContentClick); @@ -123,6 +126,11 @@ private void InitializeComponent() resources.ApplyResources(this.Extra, "Extra"); this.Extra.Name = "Extra"; // + // Write + // + resources.ApplyResources(this.Write, "Write"); + this.Write.Name = "Write"; + // // Go // resources.ApplyResources(this.Go, "Go"); @@ -155,6 +163,7 @@ private void InitializeComponent() private System.Windows.Forms.DataGridViewComboBoxColumn Direction; private System.Windows.Forms.DataGridViewTextBoxColumn Port; private System.Windows.Forms.DataGridViewTextBoxColumn Extra; + private System.Windows.Forms.DataGridViewCheckBoxColumn Write; private System.Windows.Forms.DataGridViewButtonColumn Go; } } \ No newline at end of file diff --git a/Controls/SerialOutputPass.cs b/Controls/SerialOutputPass.cs index bc53c77fee..75f38803ee 100644 --- a/Controls/SerialOutputPass.cs +++ b/Controls/SerialOutputPass.cs @@ -1,4 +1,5 @@ -using Microsoft.Scripting.Utils; +using DeviceProgramming.Dfu; +using Microsoft.Scripting.Utils; using MissionPlanner.Comms; using MissionPlanner.Utilities; using Newtonsoft.Json; @@ -131,15 +132,17 @@ private void BUT_connect_Click(object sender, EventArgs e) void DoAcceptTcpClientCallback(IAsyncResult ar) { // Get the listener that handles the client request. - TcpListener listener = (TcpListener)ar.AsyncState; + var state = (ValueTuple)ar.AsyncState; + TcpListener listener = state.Item1; + MAVLinkInterface.Mirror mirror = state.Item2; // End the operation and display the received data on // the console. TcpClient client = listener.EndAcceptTcpClient(ar); - ((TcpSerial)MainV2.comPort.MirrorStream).client = client; + ((TcpSerial)mirror.MirrorStream).client = client; - listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), listener); + listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), state); } private void chk_write_CheckedChanged(object sender, EventArgs e) @@ -165,7 +168,7 @@ private void Save() Settings.Instance.SetList(configlist, ans); } - private void Load() + private void Load() { var ans = Settings.Instance.GetList(configlist); @@ -174,11 +177,17 @@ private void Load() if (row == null || row == "") continue; var data = ((JArray)JsonConvert.DeserializeObject(row)).Select(a => ((JValue)a).Value).ToArray(); - myDataGridView1.Rows.Add(data); + var index = myDataGridView1.Rows.Add(data); + + if (Started.Contains(index)) + { + myDataGridView1[Go.Index, index].Value = "Started"; + } } } string configlist = "serialpasslist"; + static private List Started = new List(); private void myDataGridView1_DataError(object sender, DataGridViewDataErrorEventArgs e) { @@ -191,26 +200,31 @@ private void myDataGridView1_CellContentClick(object sender, DataGridViewCellEve { try { + MAVLinkInterface.Mirror mirror = new MAVLinkInterface.Mirror(); + var protocol = myDataGridView1[Type.Index, e.RowIndex].Value.ToString(); var direction = myDataGridView1[Direction.Index, e.RowIndex].Value.ToString(); var port = myDataGridView1[Port.Index, e.RowIndex].Value.ToString(); var extra = myDataGridView1[Extra.Index, e.RowIndex].Value.ToString(); + var write = myDataGridView1[Write.Index, e.RowIndex].Value.ToString(); if (protocol == "TCP") { if (direction == "Inbound") - { - MainV2.comPort.MirrorStream = new TcpSerial(); + { + mirror.MirrorStream = new TcpSerial(); + mirror.MirrorStreamWrite = bool.Parse(write); CMB_baudrate.SelectedIndex = 0; listener = new TcpListener(System.Net.IPAddress.Any, int.Parse(port.ToString())); listener.Start(0); - listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), listener); + listener.BeginAcceptTcpClient(new AsyncCallback(DoAcceptTcpClientCallback), (listener, mirror)); BUT_connect.Text = Strings.Stop; } else if (direction == "Outbound") { - MainV2.comPort.MirrorStream = new TcpSerial() { retrys = 999999, autoReconnect = true, Host = extra, Port = port, ConfigRef = "SerialOutputPassTCP" }; + mirror.MirrorStream = new TcpSerial() { retrys = 999999, autoReconnect = true, Host = extra, Port = port, ConfigRef = "SerialOutputPassTCP" }; CMB_baudrate.SelectedIndex = 0; - MainV2.comPort.MirrorStream.Open(); + mirror.MirrorStream.Open(); + mirror.MirrorStreamWrite = bool.Parse(write); } } else if (protocol == "UDP") @@ -220,9 +234,11 @@ private void myDataGridView1_CellContentClick(object sender, DataGridViewCellEve var udp = new UdpSerial() { ConfigRef = "SerialOutputPassUDP", Port = port.ToString() }; udp.client = new UdpClient(int.Parse(port)); - MainV2.comPort.MirrorStream = udp; + mirror.MirrorStream = udp; + udp.IsOpen = true; CMB_baudrate.SelectedIndex = 0; - MainV2.comPort.MirrorStream.Open(); + mirror.MirrorStream.Open(); + mirror.MirrorStreamWrite = bool.Parse(write); } else if (direction == "Outbound") { @@ -230,17 +246,23 @@ private void myDataGridView1_CellContentClick(object sender, DataGridViewCellEve udp.hostEndPoint = new IPEndPoint(IPAddress.Parse(extra), int.Parse(port)); udp.client = new UdpClient(); udp.IsOpen = true; - MainV2.comPort.MirrorStream = udp; + mirror.MirrorStream = udp; + mirror.MirrorStreamWrite = bool.Parse(write); CMB_baudrate.SelectedIndex = 0; } } else if (protocol == "Serial") { - MainV2.comPort.MirrorStream = new SerialPort(); - MainV2.comPort.MirrorStream.PortName = port; - MainV2.comPort.MirrorStream.BaudRate = int.Parse(extra); - MainV2.comPort.MirrorStream.Open(); + mirror.MirrorStream = new SerialPort(); + mirror.MirrorStream.PortName = port; + mirror.MirrorStream.BaudRate = int.Parse(extra); + mirror.MirrorStream.Open(); + mirror.MirrorStreamWrite = bool.Parse(write); } + + MainV2.comPort.Mirrors.Add(mirror); + myDataGridView1[Go.Index, e.RowIndex].Value = "Started"; + Started.Add(e.RowIndex); } catch (Exception ex) { CustomMessageBox.Show("Error: " + ex.Message); diff --git a/Controls/SerialOutputPass.resx b/Controls/SerialOutputPass.resx index 8ca2592752..63401d9f06 100644 --- a/Controls/SerialOutputPass.resx +++ b/Controls/SerialOutputPass.resx @@ -128,6 +128,9 @@ 0 + + False + CMB_serialport @@ -156,6 +159,9 @@ Connect + + False + BUT_connect @@ -201,6 +207,9 @@ 2 + + False + CMB_baudrate @@ -231,6 +240,9 @@ Write access + + False + chk_write @@ -282,6 +294,15 @@ 80 + + True + + + Write + + + 40 + True @@ -295,7 +316,7 @@ 12, 69 - 363, 150 + 428, 150 4 @@ -304,7 +325,7 @@ myDataGridView1 - MissionPlanner.Controls.MyDataGridView, MissionPlanner, Version=1.3.8177.19206, Culture=neutral, PublicKeyToken=null + MissionPlanner.Controls.MyDataGridView, MissionPlanner, Version=1.3.9076.24256, Culture=neutral, PublicKeyToken=null $this @@ -316,7 +337,7 @@ True - 387, 228 + 452, 228 @@ -394,9 +415,6 @@ AAf4AAAP/AAAH/4AAD//gAD//+AD//////8= - - NoControl - SerialOutput - Mavlink @@ -424,6 +442,12 @@ System.Windows.Forms.DataGridViewTextBoxColumn, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + Write + + + System.Windows.Forms.DataGridViewCheckBoxColumn, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + Go diff --git a/Controls/paramcompare.cs b/Controls/paramcompare.cs index 934eb1067e..c6f0389f6e 100644 --- a/Controls/paramcompare.cs +++ b/Controls/paramcompare.cs @@ -41,7 +41,7 @@ void processToScreen() if (param.ContainsKey(value) && param2.ContainsKey(value)) { // check double != double - if (param[value] != param2[value]) + if (param[value].ToString() != param2[value].ToString()) // this will throw is there is no matching key { Console.WriteLine("{0} {1} vs {2}", value, param[value], param2[value]); diff --git a/ExtLibs/ArduPilot/CurrentState.cs b/ExtLibs/ArduPilot/CurrentState.cs index 16eec0d3ed..3fb2792786 100644 --- a/ExtLibs/ArduPilot/CurrentState.cs +++ b/ExtLibs/ArduPilot/CurrentState.cs @@ -4051,10 +4051,23 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi ahrs2_lng = ahrs2.lng / 1e7; } break; + case (uint)MAVLink.MAVLINK_MSG_ID.AIRSPEED: + { + var airspeedp = mavLinkMessage.ToStructure(); + + if(airspeedp.id == 0) + { + airspeed = airspeedp.airspeed; + airspeed1_temp = (float)(airspeedp.temperature / 100.0); + } + } + break; case (uint)MAVLink.MAVLINK_MSG_ID.CAN_FRAME: case (uint)MAVLink.MAVLINK_MSG_ID.CANFD_FRAME: case (uint)MAVLink.MAVLINK_MSG_ID.FILE_TRANSFER_PROTOCOL: case (uint)MAVLink.MAVLINK_MSG_ID.LOG_DATA: + case (uint)MAVLink.MAVLINK_MSG_ID.DEVICE_OP_WRITE_REPLY: + case (uint)MAVLink.MAVLINK_MSG_ID.TIMESYNC: break; default: { diff --git a/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs b/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs index c617fce79f..46b2c07e58 100644 --- a/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs +++ b/ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs @@ -165,8 +165,13 @@ public static event EventHandler UpdateADSBPlanePosition } } - public ICommsSerial MirrorStream { get; set; } - public bool MirrorStreamWrite { get; set; } + public class Mirror + { + public ICommsSerial MirrorStream { get; set; } + public bool MirrorStreamWrite { get; set; } + } + + public List Mirrors { get; set; } = new List(); public event EventHandler ParamListChanged { @@ -419,6 +424,41 @@ public BinaryReader logplaybackfile private int _bps2 = 0; private DateTime _bpstime { get; set; } + public bool MirrorStreamWrite { + get { + if (Mirrors.Count > 0) + return Mirrors[0].MirrorStreamWrite; + + Mirrors.Add(new Mirror()); + return MirrorStreamWrite; + } + set + { + if (Mirrors.Count > 0) + Mirrors[0].MirrorStreamWrite = value; + else + Mirrors.Add(new Mirror() { MirrorStreamWrite = value }); + } + } + public ICommsSerial MirrorStream { + get + { + if (Mirrors.Count > 0) + return Mirrors[0].MirrorStream; + + Mirrors.Add(new Mirror()); + return MirrorStream; + } + set + { + if (Mirrors.Count > 0) + Mirrors[0].MirrorStream = value; + else + Mirrors.Add(new Mirror() { MirrorStream = value }); + } + } + + public static ISpeech Speech; ~MAVLinkInterface() @@ -4359,7 +4399,7 @@ public void setGuidedModeWP(byte sysid, byte compid, Locationwp gotohere, bool s if (MAVlist[sysid, compid].cs.firmware == Firmwares.ArduPlane) { - MAV_MISSION_RESULT ans = setWP(sysid, compid, gotohere, 0, MAV_FRAME.GLOBAL_RELATIVE_ALT, (byte) 2); + MAV_MISSION_RESULT ans = setWP(sysid, compid, gotohere, 0, (MAV_FRAME)gotohere.frame, (byte) 2); if (ans != MAV_MISSION_RESULT.MAV_MISSION_ACCEPTED) { @@ -5385,34 +5425,39 @@ public async Task readPacketAsync() private void ProcessMirrorStream(byte[] buffer) { - try + foreach (var Mirror in Mirrors) { - // full rw from mirror stream - if (MirrorStream != null && MirrorStream.IsOpen) + var MirrorStream = Mirror.MirrorStream; + try { - MirrorStream.Write(buffer, 0, buffer.Length); - - while (MirrorStream.BytesToRead > 0) + // full rw from mirror stream + if (MirrorStream != null && MirrorStream.IsOpen) { - var len = MirrorStream.BytesToRead; + MirrorStream.Write(buffer, 0, buffer.Length); - byte[] buf = new byte[len]; + while (MirrorStream.BytesToRead > 0) + { + var len = MirrorStream.BytesToRead; - len = MirrorStream.Read(buf, 0, len); + byte[] buf = new byte[len]; - if (MirrorStreamWrite) - lock (writelock) - { - BaseStream.Write(buf, 0, len); + len = MirrorStream.Read(buf, 0, len); - if (rawlogfile != null && rawlogfile.CanWrite) - rawlogfile.Write(buf, 0, len); - } + if (Mirror.MirrorStreamWrite) + lock (writelock) + { + BaseStream.Write(buf, 0, len); + + if (rawlogfile != null && rawlogfile.CanWrite) + rawlogfile.Write(buf, 0, len); + } + } } + + } + catch + { } - } - catch - { } } @@ -6758,7 +6803,7 @@ public void Dispose() Terrain?.UnSub(); Terrain = null; - MirrorStream = null; + Mirrors.Clear(); logreadmode = false; logplaybackfile = null; diff --git a/ExtLibs/Comms/CommsBLE.cs b/ExtLibs/Comms/CommsBLE.cs index 0ce8e85713..9ea6cc3a94 100644 --- a/ExtLibs/Comms/CommsBLE.cs +++ b/ExtLibs/Comms/CommsBLE.cs @@ -70,7 +70,6 @@ public override void Flush() } - static simpleble_adapter_t adapter; public void Open() { @@ -82,144 +81,152 @@ public void Open() if (IsOpen) return; - lock (locker) + // only one instance of the scan + if (Monitor.TryEnter(locker)) { - if(adapter == null) - adapter = simpleble_adapter_get_handle(0); - - if (adapter == null) + try { - throw new Exception("No adapter was found.\n"); - return; - } + if (adapter == null) + adapter = simpleble_adapter_get_handle(0); + + if (adapter == null) + { + throw new Exception("No adapter was found.\n"); + return; + } - simpleble_adapter_set_callback_on_scan_start(adapter, adapter_on_scan_start, null); - simpleble_adapter_set_callback_on_scan_stop(adapter, adapter_on_scan_stop, null); - simpleble_adapter_set_callback_on_scan_found(adapter, adapter_on_scan_found, null); - simpleble_adapter_set_callback_on_scan_updated(adapter, adapter_on_scan_updated, null); + simpleble_adapter_set_callback_on_scan_start(adapter, adapter_on_scan_start, null); + simpleble_adapter_set_callback_on_scan_stop(adapter, adapter_on_scan_stop, null); + simpleble_adapter_set_callback_on_scan_found(adapter, adapter_on_scan_found, null); + simpleble_adapter_set_callback_on_scan_updated(adapter, adapter_on_scan_updated, null); - simpleble_adapter_scan_for(adapter, 5000); + simpleble_adapter_scan_for(adapter, 5000); - simpleble_adapter_set_callback_on_scan_start(adapter, null, null); - simpleble_adapter_set_callback_on_scan_stop(adapter, null, null); - simpleble_adapter_set_callback_on_scan_found(adapter, null, null); - simpleble_adapter_set_callback_on_scan_updated(adapter, null, null); + simpleble_adapter_set_callback_on_scan_start(adapter, null, null); + simpleble_adapter_set_callback_on_scan_stop(adapter, null, null); + simpleble_adapter_set_callback_on_scan_found(adapter, null, null); + simpleble_adapter_set_callback_on_scan_updated(adapter, null, null); - size_t useindex = -1; + size_t useindex = -1; - size_t peripheral_count = simpleble_adapter_scan_get_results_count(adapter); - for (size_t peripheral_index = 0; peripheral_index < peripheral_count; peripheral_index++) - { - var peripheral = simpleble_adapter_scan_get_results_handle(adapter, peripheral_index); + size_t peripheral_count = simpleble_adapter_scan_get_results_count(adapter); + for (size_t peripheral_index = 0; peripheral_index < peripheral_count; peripheral_index++) + { + var peripheral = simpleble_adapter_scan_get_results_handle(adapter, peripheral_index); - string peripheral_identifier = simpleble_peripheral_identifier(peripheral); - string peripheral_address = simpleble_peripheral_address(peripheral); + string peripheral_identifier = simpleble_peripheral_identifier(peripheral); + string peripheral_address = simpleble_peripheral_address(peripheral); - bool peripheral_connectable = false; - simpleble_peripheral_is_connectable(peripheral, out peripheral_connectable); + bool peripheral_connectable = false; + simpleble_peripheral_is_connectable(peripheral, out peripheral_connectable); - int16_t peripheral_rssi = simpleble_peripheral_rssi(peripheral); + int16_t peripheral_rssi = simpleble_peripheral_rssi(peripheral); - printf("[{0}] {1} [{2}] {3} dBm {4}\n", peripheral_index, peripheral_identifier, peripheral_address, - peripheral_rssi, peripheral_connectable ? "Connectable" : "Non-Connectable"); + printf("[{0}] {1} [{2}] {3} dBm {4}\n", peripheral_index, peripheral_identifier, peripheral_address, + peripheral_rssi, peripheral_connectable ? "Connectable" : "Non-Connectable"); - if (PortName.Contains(peripheral_address.ToLower().Replace(":", ""))) - { - size_t services_count = simpleble_peripheral_services_count(peripheral); - for (size_t service_index = 0; service_index < services_count; service_index++) + if (PortName.Contains(peripheral_address.ToLower().Replace(":", ""))) { - simpleble_service_t service = default; - simpleble_peripheral_services_get(peripheral, service_index, ref service); + size_t services_count = simpleble_peripheral_services_count(peripheral); + for (size_t service_index = 0; service_index < services_count; service_index++) + { + simpleble_service_t service = default; + simpleble_peripheral_services_get(peripheral, service_index, ref service); + + printf(" Service UUID: {0}\n", service.uuid.valueuuid); + printf(" Service data: "); + print_buffer_hex(service.data, service.data_length, true); - printf(" Service UUID: {0}\n", service.uuid.valueuuid); - printf(" Service data: "); - print_buffer_hex(service.data, service.data_length, true); + useindex = peripheral_index; + } + } - useindex = peripheral_index; + size_t manufacturer_data_count = simpleble_peripheral_manufacturer_data_count(peripheral); + for (size_t manuf_data_index = 0; manuf_data_index < manufacturer_data_count; manuf_data_index++) + { + simpleble_manufacturer_data_t manuf_data = default; + simpleble_peripheral_manufacturer_data_get(peripheral, manuf_data_index, ref manuf_data); + printf(" Manufacturer ID: {0}\n", manuf_data.manufacturer_id); + printf(" Manufacturer data: "); + print_buffer_hex(manuf_data.data, manuf_data.data_length, true); } + + // Let's not forget to release the associated handles and memory + simpleble_peripheral_release_handle(peripheral); + peripheral = IntPtr.Zero; + //simpleble_free(peripheral_address); + //simpleble_free(peripheral_identifier); } - size_t manufacturer_data_count = simpleble_peripheral_manufacturer_data_count(peripheral); - for (size_t manuf_data_index = 0; manuf_data_index < manufacturer_data_count; manuf_data_index++) + if (useindex == -1) { - simpleble_manufacturer_data_t manuf_data = default; - simpleble_peripheral_manufacturer_data_get(peripheral, manuf_data_index, ref manuf_data); - printf(" Manufacturer ID: {0}\n", manuf_data.manufacturer_id); - printf(" Manufacturer data: "); - print_buffer_hex(manuf_data.data, manuf_data.data_length, true); + throw new Exception("Could not find device"); } - // Let's not forget to release the associated handles and memory - simpleble_peripheral_release_handle(peripheral); - //simpleble_free(peripheral_address); - //simpleble_free(peripheral_identifier); - } - - if (useindex == -1) - { - throw new Exception("Could not find device"); - } - - { - peripheral = simpleble_adapter_scan_get_results_handle(adapter, useindex); - string peripheral_address = simpleble_peripheral_address(peripheral); - bleperiph = this; - - _callbackperipheral_on_connected = new MyCallbackp2(peripheral_on_connected); - _callbackperipheral_on_disconnected = new MyCallbackp2(peripheral_on_disconnected); - - simpleble_peripheral_set_callback_on_connected(peripheral, _callbackperipheral_on_connected, null); - simpleble_peripheral_set_callback_on_disconnected(peripheral, _callbackperipheral_on_disconnected, null); - - - var err_code = simpleble_peripheral_connect(peripheral); - if (err_code != simpleble_err_t.SIMPLEBLE_SUCCESS) { - throw new Exception("Failed to connect.\n"); - return; - } + peripheral = simpleble_adapter_scan_get_results_handle(adapter, useindex); + string peripheral_address = simpleble_peripheral_address(peripheral); + bleperiph = this; - size_t services_count = simpleble_peripheral_services_count(peripheral); - printf("Successfully connected, listing {0} services.\n", services_count); + _callbackperipheral_on_connected = new MyCallbackp2(peripheral_on_connected); + _callbackperipheral_on_disconnected = new MyCallbackp2(peripheral_on_disconnected); - for (size_t i = 0; i < services_count; i++) - { - simpleble_service_t service = default; - err_code = simpleble_peripheral_services_get(peripheral, i, ref service); + simpleble_peripheral_set_callback_on_connected(peripheral, _callbackperipheral_on_connected, null); + simpleble_peripheral_set_callback_on_disconnected(peripheral, _callbackperipheral_on_disconnected, null); + + var err_code = simpleble_peripheral_connect(peripheral); if (err_code != simpleble_err_t.SIMPLEBLE_SUCCESS) { - throw new Exception("Failed to get service.\n"); + throw new Exception("Failed to connect.\n"); return; } - printf("Service: {0} - ({1} characteristics)\n", service.uuid.valueuuid, service.characteristic_count); - for (size_t j = 0; j < service.characteristic_count; j++) + size_t services_count = simpleble_peripheral_services_count(peripheral); + printf("Successfully connected, listing {0} services.\n", services_count); + + for (size_t i = 0; i < services_count; i++) { - printf(" Characteristic: {0} - ({1} descriptors)\n", service.characteristics[j].uuid.valueuuid, - service.characteristics[j].descriptor_count); - for (size_t k = 0; k < service.characteristics[j].descriptor_count; k++) + simpleble_service_t service = default; + err_code = simpleble_peripheral_services_get(peripheral, i, ref service); + + if (err_code != simpleble_err_t.SIMPLEBLE_SUCCESS) + { + throw new Exception("Failed to get service.\n"); + return; + } + + printf("Service: {0} - ({1} characteristics)\n", service.uuid.valueuuid, service.characteristic_count); + for (size_t j = 0; j < service.characteristic_count; j++) { - printf(" Descriptor: {0}\n", service.characteristics[j].descriptors[k].uuid.valueuuid); + printf(" Characteristic: {0} - ({1} descriptors)\n", service.characteristics[j].uuid.valueuuid, + service.characteristics[j].descriptor_count); + for (size_t k = 0; k < service.characteristics[j].descriptor_count; k++) + { + printf(" Descriptor: {0}\n", service.characteristics[j].descriptors[k].uuid.valueuuid); + } } } - } - bool paired = false; - //while (!paired) - { - mtu = simpleble_peripheral_mtu(peripheral); - Console.WriteLine("MTU: " + mtu); - simpleble_peripheral_is_connected(peripheral, out paired); - //simpleble_peripheral_is_paired(peripheral, out paired); - Thread.Sleep(1000); - Console.WriteLine("Waiting for pairing/connected"); - } + bool paired = false; + //while (!paired) + { + mtu = simpleble_peripheral_mtu(peripheral); + Console.WriteLine("MTU: " + mtu); + simpleble_peripheral_is_connected(peripheral, out paired); + //simpleble_peripheral_is_paired(peripheral, out paired); + Thread.Sleep(1000); + Console.WriteLine("Waiting for pairing/connected"); + } - IsOpen = true; + IsOpen = true; + } + } + finally + { + Monitor.Exit(locker); } } - } static object locker = new object(); @@ -237,11 +244,13 @@ public static List SerialPort_GetCustomPorts() // run scan in the background - and only one Task.Run(() => { - lock (locker) + if (Monitor.TryEnter(locker)) { try { - if(adapter == IntPtr.Zero) + simpleble_adapter_t adapter = IntPtr.Zero; + + if (adapter == IntPtr.Zero) adapter = simpleble_adapter_get_handle(0); if (adapter == null) { @@ -300,11 +309,17 @@ public static List SerialPort_GetCustomPorts() } simpleble_peripheral_release_handle(peripheral); + peripheral = IntPtr.Zero; } - //simpleble_adapter_release_handle(adapter); + simpleble_adapter_release_handle(adapter); + adapter = IntPtr.Zero; } catch { } + finally + { + Monitor.Exit(locker); + } } }); @@ -698,6 +713,7 @@ static byte[] GUIDtoByteArray(string guid) private MyCallbackp2 _callbackperipheral_on_connected; private MyCallbackp2 _callbackperipheral_on_disconnected; private ushort mtu; + private simpleble_adapter_t adapter; private static void Send(simpleble_peripheral_t peripheral, byte[] data, int offset, int length) { diff --git a/ExtLibs/Controls/AltInputBox.cs b/ExtLibs/Controls/AltInputBox.cs new file mode 100644 index 0000000000..d64c25572d --- /dev/null +++ b/ExtLibs/Controls/AltInputBox.cs @@ -0,0 +1,141 @@ +using System.Collections.Generic; +using System.Drawing; +using System.Linq; +using System.Windows.Forms; + +namespace MissionPlanner.Controls +{ + public class AltInputBox + { + public delegate void ThemeManager(Control ctl); + public static event ThemeManager ApplyTheme; + + public static string alt = ""; + public static MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT; // Holds the altitude frame selection + + public static DialogResult Show(string title, string promptText, ref string alt, ref MAVLink.MAV_FRAME frame) + { + DialogResult answer = DialogResult.Cancel; + AltInputBox.alt = alt; + AltInputBox.frame = frame; + + // ensure we run this on the right thread - mono - mac + if (Application.OpenForms.Count > 0 && Application.OpenForms[0].InvokeRequired) + { + Application.OpenForms[0].Invoke((MethodInvoker)delegate + { + answer = ShowUI(title, promptText); + }); + } + else + { + answer = ShowUI(title, promptText); + } + + alt = AltInputBox.alt; + frame = AltInputBox.frame; + + return answer; + } + + static DialogResult ShowUI(string title, string promptText) + { + Form form = new Form(); + Label label = new Label(); + TextBox textBoxAlt = new TextBox(); + ComboBox comboBoxFrame = new ComboBox(); + MyButton buttonOk = new MyButton(); + MyButton buttonCancel = new MyButton(); + + // Form layout setup + form.SuspendLayout(); + const int yMargin = 10; + const int xMargin = 10; + + form.TopMost = true; + form.TopLevel = true; + form.Text = title; + form.ClientSize = new Size(396, 150); // Keep the same form width + form.FormBorderStyle = FormBorderStyle.FixedSingle; + form.StartPosition = FormStartPosition.CenterScreen; + form.MinimizeBox = false; + form.MaximizeBox = false; + + // Label for the prompt text + var y = 20; + label.AutoSize = true; + label.Location = new Point(9, y); + label.Size = new Size(372, 13); + label.Text = promptText; + label.MaximumSize = new Size(372, 0); + + // ComboBox for altitude frame selection (reduce width, aligned next to TextBox) + comboBoxFrame.Size = new Size(70, 20); + comboBoxFrame.DropDownStyle = ComboBoxStyle.DropDownList; + + // Add KeyValuePair items for each option + comboBoxFrame.Items.Add(new KeyValuePair("Absolute", MAVLink.MAV_FRAME.GLOBAL)); + comboBoxFrame.Items.Add(new KeyValuePair("Relative", MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT)); + comboBoxFrame.Items.Add(new KeyValuePair("Terrain", MAVLink.MAV_FRAME.GLOBAL_TERRAIN_ALT)); + comboBoxFrame.DisplayMember = "Key"; + comboBoxFrame.ValueMember = "Value"; + + // Set the initial selected value by matching the frameValue + comboBoxFrame.SelectedIndex = comboBoxFrame.Items.Cast>() + .ToList().FindIndex(item => item.Value == frame); + + // TextBox for altitude input + textBoxAlt.Size = new Size(form.ClientSize.Width - comboBoxFrame.Width - 3 * xMargin, 20); + textBoxAlt.Text = alt; + + // OK Button + buttonOk.Size = new Size(75, 23); + buttonOk.Text = "OK"; + buttonOk.DialogResult = DialogResult.OK; + + // Cancel Button + buttonCancel.Size = new Size(75, 23); + buttonCancel.Text = "Cancel"; + buttonCancel.DialogResult = DialogResult.Cancel; + + // Add controls to the form + form.Controls.Add(label); + form.Controls.Add(textBoxAlt); + form.Controls.Add(comboBoxFrame); + form.Controls.Add(buttonOk); + form.Controls.Add(buttonCancel); + + form.AcceptButton = buttonOk; + form.CancelButton = buttonCancel; + + // Resume layout + form.ResumeLayout(false); + form.PerformLayout(); + + // Adjust the location of textBox, buttonOk, buttonCancel based on the content of the label. + y = y + label.Height + yMargin; + comboBoxFrame.Location = new Point(xMargin, y); + textBoxAlt.Location = new Point(comboBoxFrame.Location.X + comboBoxFrame.Width + xMargin, y + 4); + y = y + textBoxAlt.Height + yMargin; + buttonOk.Location = new Point(228, y); + buttonCancel.Location = new Point(309, y); + // Increase the size of the form. + form.ClientSize = new Size(396, y + buttonOk.Height + yMargin); + + // Apply any theme settings + ApplyTheme?.Invoke(form); + + // Show the form and return the result + DialogResult dialogResult = form.ShowDialog(); + + if (dialogResult == DialogResult.OK) + { + alt = textBoxAlt.Text; + frame = (MAVLink.MAV_FRAME)((dynamic)comboBoxFrame.SelectedItem).Value; + } + + form.Dispose(); + return dialogResult; + } + } +} diff --git a/ExtLibs/Mavlink/Mavlink.cs b/ExtLibs/Mavlink/Mavlink.cs index c582d5d578..7a47b47541 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 Oct 05 2024"; + public const string MAVLINK_BUILD_DATE = "Mon Nov 18 2024"; public const string MAVLINK_WIRE_PROTOCOL_VERSION = "2.0"; public const int MAVLINK_MAX_PAYLOAD_LEN = 255; @@ -37,6 +37,7 @@ public partial class MAVLink // msgid, name, crc, minlength, length, type public static message_info[] MAVLINK_MESSAGE_INFOS = new message_info[] { + new message_info(0, "HEARTBEAT", 50, 9, 9, typeof( mavlink_heartbeat_t )), new message_info(1, "SYS_STATUS", 124, 31, 31, typeof( mavlink_sys_status_t )), new message_info(2, "SYSTEM_TIME", 137, 12, 12, typeof( mavlink_system_time_t )), new message_info(4, "PING", 237, 14, 14, typeof( mavlink_ping_t )), @@ -76,6 +77,7 @@ public partial class MAVLink new message_info(49, "GPS_GLOBAL_ORIGIN", 39, 12, 20, typeof( mavlink_gps_global_origin_t )), new message_info(50, "PARAM_MAP_RC", 78, 37, 37, typeof( mavlink_param_map_rc_t )), new message_info(51, "MISSION_REQUEST_INT", 196, 4, 5, typeof( mavlink_mission_request_int_t )), + new message_info(53, "MISSION_CHECKSUM", 3, 5, 5, typeof( mavlink_mission_checksum_t )), new message_info(54, "SAFETY_SET_ALLOWED_AREA", 15, 27, 27, typeof( mavlink_safety_set_allowed_area_t )), new message_info(55, "SAFETY_ALLOWED_AREA", 3, 25, 25, typeof( mavlink_safety_allowed_area_t )), new message_info(61, "ATTITUDE_QUATERNION_COV", 167, 72, 72, typeof( mavlink_attitude_quaternion_cov_t )), @@ -202,6 +204,11 @@ public partial class MAVLink new message_info(217, "GOPRO_GET_RESPONSE", 202, 6, 6, typeof( mavlink_gopro_get_response_t )), new message_info(218, "GOPRO_SET_REQUEST", 17, 7, 7, typeof( mavlink_gopro_set_request_t )), new message_info(219, "GOPRO_SET_RESPONSE", 162, 2, 2, typeof( mavlink_gopro_set_response_t )), + new message_info(220, "NAV_FILTER_BIAS", 34, 32, 32, typeof( mavlink_nav_filter_bias_t )), + new message_info(221, "RADIO_CALIBRATION", 71, 42, 42, typeof( mavlink_radio_calibration_t )), + new message_info(222, "UALBERTA_SYS_STATUS", 15, 3, 3, typeof( mavlink_ualberta_sys_status_t )), + new message_info(223, "COMMAND_INT_STAMPED", 119, 47, 47, typeof( mavlink_command_int_stamped_t )), + new message_info(224, "COMMAND_LONG_STAMPED", 102, 45, 45, typeof( mavlink_command_long_stamped_t )), new message_info(225, "EFI_STATUS", 208, 65, 73, typeof( mavlink_efi_status_t )), new message_info(226, "RPM", 207, 8, 8, typeof( mavlink_rpm_t )), new message_info(230, "ESTIMATOR_STATUS", 163, 42, 42, typeof( mavlink_estimator_status_t )), @@ -252,6 +259,7 @@ public partial class MAVLink 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(295, "AIRSPEED", 234, 12, 12, typeof( mavlink_airspeed_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 )), @@ -263,6 +271,8 @@ public partial class MAVLink new message_info(324, "PARAM_EXT_ACK", 132, 146, 146, typeof( mavlink_param_ext_ack_t )), new message_info(330, "OBSTACLE_DISTANCE", 23, 158, 167, typeof( mavlink_obstacle_distance_t )), new message_info(331, "ODOMETRY", 91, 230, 233, typeof( mavlink_odometry_t )), + new message_info(332, "TRAJECTORY_REPRESENTATION_WAYPOINTS", 236, 239, 239, typeof( mavlink_trajectory_representation_waypoints_t )), + new message_info(333, "TRAJECTORY_REPRESENTATION_BEZIER", 231, 109, 109, typeof( mavlink_trajectory_representation_bezier_t )), new message_info(335, "ISBD_LINK_STATUS", 225, 24, 24, typeof( mavlink_isbd_link_status_t )), new message_info(339, "RAW_RPM", 199, 5, 5, typeof( mavlink_raw_rpm_t )), new message_info(340, "UTM_GLOBAL_POSITION", 99, 70, 70, typeof( mavlink_utm_global_position_t )), @@ -275,6 +285,26 @@ public partial class MAVLink 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 )), new message_info(388, "CAN_FILTER_MODIFY", 8, 37, 37, typeof( mavlink_can_filter_modify_t )), + new message_info(420, "RADIO_RC_CHANNELS", 20, 9, 73, typeof( mavlink_radio_rc_channels_t )), + new message_info(435, "AVAILABLE_MODES", 134, 46, 46, typeof( mavlink_available_modes_t )), + new message_info(436, "CURRENT_MODE", 193, 9, 9, typeof( mavlink_current_mode_t )), + new message_info(437, "AVAILABLE_MODES_MONITOR", 30, 1, 1, typeof( mavlink_available_modes_monitor_t )), + new message_info(441, "GNSS_INTEGRITY", 169, 17, 17, typeof( mavlink_gnss_integrity_t )), + new message_info(8002, "SENS_POWER", 218, 16, 16, typeof( mavlink_sens_power_t )), + new message_info(8003, "SENS_MPPT", 231, 41, 41, typeof( mavlink_sens_mppt_t )), + new message_info(8004, "ASLCTRL_DATA", 172, 98, 98, typeof( mavlink_aslctrl_data_t )), + new message_info(8005, "ASLCTRL_DEBUG", 251, 38, 38, typeof( mavlink_aslctrl_debug_t )), + new message_info(8006, "ASLUAV_STATUS", 97, 14, 14, typeof( mavlink_asluav_status_t )), + new message_info(8007, "EKF_EXT", 64, 32, 32, typeof( mavlink_ekf_ext_t )), + new message_info(8008, "ASL_OBCTRL", 234, 33, 33, typeof( mavlink_asl_obctrl_t )), + new message_info(8009, "SENS_ATMOS", 144, 16, 16, typeof( mavlink_sens_atmos_t )), + new message_info(8010, "SENS_BATMON", 155, 41, 41, typeof( mavlink_sens_batmon_t )), + new message_info(8011, "FW_SOARING_DATA", 20, 102, 102, typeof( mavlink_fw_soaring_data_t )), + new message_info(8012, "SENSORPOD_STATUS", 54, 16, 16, typeof( mavlink_sensorpod_status_t )), + new message_info(8013, "SENS_POWER_BOARD", 222, 46, 46, typeof( mavlink_sens_power_board_t )), + new message_info(8014, "GSM_LINK_STATUS", 200, 14, 14, typeof( mavlink_gsm_link_status_t )), + new message_info(8015, "SATCOM_LINK_STATUS", 23, 24, 24, typeof( mavlink_satcom_link_status_t )), + new message_info(8016, "SENSOR_AIRFLOW_ANGLES", 149, 18, 18, typeof( mavlink_sensor_airflow_angles_t )), new message_info(9000, "WHEEL_DISTANCE", 113, 137, 137, typeof( mavlink_wheel_distance_t )), new message_info(9005, "WINCH_STATUS", 117, 34, 34, typeof( mavlink_winch_status_t )), new message_info(10001, "UAVIONIX_ADSB_OUT_CFG", 209, 20, 20, typeof( mavlink_uavionix_adsb_out_cfg_t )), @@ -320,6 +350,15 @@ public partial class MAVLink new message_info(12918, "OPEN_DRONE_ID_ARM_STATUS", 139, 51, 51, typeof( mavlink_open_drone_id_arm_status_t )), new message_info(12919, "OPEN_DRONE_ID_SYSTEM_UPDATE", 7, 18, 18, typeof( mavlink_open_drone_id_system_update_t )), new message_info(12920, "HYGROMETER_SENSOR", 20, 5, 5, typeof( mavlink_hygrometer_sensor_t )), + new message_info(17000, "TEST_TYPES", 103, 179, 179, typeof( mavlink_test_types_t )), + new message_info(17150, "ARRAY_TEST_0", 26, 33, 33, typeof( mavlink_array_test_0_t )), + new message_info(17151, "ARRAY_TEST_1", 72, 16, 16, typeof( mavlink_array_test_1_t )), + new message_info(17153, "ARRAY_TEST_3", 19, 17, 17, typeof( mavlink_array_test_3_t )), + new message_info(17154, "ARRAY_TEST_4", 89, 17, 17, typeof( mavlink_array_test_4_t )), + new message_info(17155, "ARRAY_TEST_5", 27, 10, 10, typeof( mavlink_array_test_5_t )), + new message_info(17156, "ARRAY_TEST_6", 14, 91, 91, typeof( mavlink_array_test_6_t )), + new message_info(17157, "ARRAY_TEST_7", 187, 84, 84, typeof( mavlink_array_test_7_t )), + new message_info(17158, "ARRAY_TEST_8", 106, 24, 24, typeof( mavlink_array_test_8_t )), new message_info(42000, "ICAROUS_HEARTBEAT", 227, 1, 1, typeof( mavlink_icarous_heartbeat_t )), new message_info(42001, "ICAROUS_KINEMATIC_BANDS", 239, 46, 46, typeof( mavlink_icarous_kinematic_bands_t )), new message_info(50001, "CUBEPILOT_RAW_RC", 246, 32, 32, typeof( mavlink_cubepilot_raw_rc_t )), @@ -329,8 +368,21 @@ public partial class MAVLink 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 )), + new message_info(60001, "STORM32_GIMBAL_DEVICE_STATUS", 186, 42, 42, typeof( mavlink_storm32_gimbal_device_status_t )), + new message_info(60002, "STORM32_GIMBAL_DEVICE_CONTROL", 69, 32, 32, typeof( mavlink_storm32_gimbal_device_control_t )), + new message_info(60010, "STORM32_GIMBAL_MANAGER_INFORMATION", 208, 33, 33, typeof( mavlink_storm32_gimbal_manager_information_t )), + new message_info(60011, "STORM32_GIMBAL_MANAGER_STATUS", 183, 7, 7, typeof( mavlink_storm32_gimbal_manager_status_t )), + new message_info(60012, "STORM32_GIMBAL_MANAGER_CONTROL", 99, 36, 36, typeof( mavlink_storm32_gimbal_manager_control_t )), + new message_info(60013, "STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW", 129, 24, 24, typeof( mavlink_storm32_gimbal_manager_control_pitchyaw_t )), + new message_info(60014, "STORM32_GIMBAL_MANAGER_CORRECT_ROLL", 134, 8, 8, typeof( mavlink_storm32_gimbal_manager_correct_roll_t )), + new message_info(60015, "STORM32_GIMBAL_MANAGER_PROFILE", 78, 22, 22, typeof( mavlink_storm32_gimbal_manager_profile_t )), + new message_info(60020, "QSHOT_STATUS", 202, 4, 4, typeof( mavlink_qshot_status_t )), + new message_info(60025, "COMPONENT_PREARM_STATUS", 20, 10, 10, typeof( mavlink_component_prearm_status_t )), + new message_info(60050, "AVSS_PRS_SYS_STATUS", 220, 14, 14, typeof( mavlink_avss_prs_sys_status_t )), + new message_info(60051, "AVSS_DRONE_POSITION", 245, 24, 24, typeof( mavlink_avss_drone_position_t )), + new message_info(60052, "AVSS_DRONE_IMU", 101, 44, 44, typeof( mavlink_avss_drone_imu_t )), + new message_info(60053, "AVSS_DRONE_OPERATION_MODE", 45, 6, 6, typeof( mavlink_avss_drone_operation_mode_t )), + new message_info(26900, "zVIDEO_STREAM_INFORMATION", 124, 246, 246, typeof( mavlink_zvideo_stream_information_t )), }; @@ -367,6 +419,7 @@ public override string ToString() public enum MAVLINK_MSG_ID { + HEARTBEAT = 0, SYS_STATUS = 1, SYSTEM_TIME = 2, PING = 4, @@ -406,6 +459,7 @@ public enum MAVLINK_MSG_ID GPS_GLOBAL_ORIGIN = 49, PARAM_MAP_RC = 50, MISSION_REQUEST_INT = 51, + MISSION_CHECKSUM = 53, SAFETY_SET_ALLOWED_AREA = 54, SAFETY_ALLOWED_AREA = 55, ATTITUDE_QUATERNION_COV = 61, @@ -532,6 +586,11 @@ public enum MAVLINK_MSG_ID GOPRO_GET_RESPONSE = 217, GOPRO_SET_REQUEST = 218, GOPRO_SET_RESPONSE = 219, + NAV_FILTER_BIAS = 220, + RADIO_CALIBRATION = 221, + UALBERTA_SYS_STATUS = 222, + COMMAND_INT_STAMPED = 223, + COMMAND_LONG_STAMPED = 224, EFI_STATUS = 225, RPM = 226, ESTIMATOR_STATUS = 230, @@ -582,6 +641,7 @@ public enum MAVLINK_MSG_ID AUTOPILOT_STATE_FOR_GIMBAL_DEVICE = 286, GIMBAL_MANAGER_SET_PITCHYAW = 287, GIMBAL_MANAGER_SET_MANUAL_CONTROL = 288, + AIRSPEED = 295, WIFI_CONFIG_AP = 299, AIS_VESSEL = 301, UAVCAN_NODE_STATUS = 310, @@ -593,6 +653,8 @@ public enum MAVLINK_MSG_ID PARAM_EXT_ACK = 324, OBSTACLE_DISTANCE = 330, ODOMETRY = 331, + TRAJECTORY_REPRESENTATION_WAYPOINTS = 332, + TRAJECTORY_REPRESENTATION_BEZIER = 333, ISBD_LINK_STATUS = 335, RAW_RPM = 339, UTM_GLOBAL_POSITION = 340, @@ -605,6 +667,26 @@ public enum MAVLINK_MSG_ID CAN_FRAME = 386, CANFD_FRAME = 387, CAN_FILTER_MODIFY = 388, + RADIO_RC_CHANNELS = 420, + AVAILABLE_MODES = 435, + CURRENT_MODE = 436, + AVAILABLE_MODES_MONITOR = 437, + GNSS_INTEGRITY = 441, + SENS_POWER = 8002, + SENS_MPPT = 8003, + ASLCTRL_DATA = 8004, + ASLCTRL_DEBUG = 8005, + ASLUAV_STATUS = 8006, + EKF_EXT = 8007, + ASL_OBCTRL = 8008, + SENS_ATMOS = 8009, + SENS_BATMON = 8010, + FW_SOARING_DATA = 8011, + SENSORPOD_STATUS = 8012, + SENS_POWER_BOARD = 8013, + GSM_LINK_STATUS = 8014, + SATCOM_LINK_STATUS = 8015, + SENSOR_AIRFLOW_ANGLES = 8016, WHEEL_DISTANCE = 9000, WINCH_STATUS = 9005, UAVIONIX_ADSB_OUT_CFG = 10001, @@ -650,6 +732,15 @@ public enum MAVLINK_MSG_ID OPEN_DRONE_ID_ARM_STATUS = 12918, OPEN_DRONE_ID_SYSTEM_UPDATE = 12919, HYGROMETER_SENSOR = 12920, + TEST_TYPES = 17000, + ARRAY_TEST_0 = 17150, + ARRAY_TEST_1 = 17151, + ARRAY_TEST_3 = 17153, + ARRAY_TEST_4 = 17154, + ARRAY_TEST_5 = 17155, + ARRAY_TEST_6 = 17156, + ARRAY_TEST_7 = 17157, + ARRAY_TEST_8 = 17158, ICAROUS_HEARTBEAT = 42000, ICAROUS_KINEMATIC_BANDS = 42001, CUBEPILOT_RAW_RC = 50001, @@ -659,11 +750,26 @@ public enum MAVLINK_MSG_ID CUBEPILOT_FIRMWARE_UPDATE_RESP = 50005, AIRLINK_AUTH = 52000, AIRLINK_AUTH_RESPONSE = 52001, - VIDEO_STREAM_INFORMATION99 = 26900, - HEARTBEAT = 0, + STORM32_GIMBAL_DEVICE_STATUS = 60001, + STORM32_GIMBAL_DEVICE_CONTROL = 60002, + STORM32_GIMBAL_MANAGER_INFORMATION = 60010, + STORM32_GIMBAL_MANAGER_STATUS = 60011, + STORM32_GIMBAL_MANAGER_CONTROL = 60012, + STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW = 60013, + STORM32_GIMBAL_MANAGER_CORRECT_ROLL = 60014, + STORM32_GIMBAL_MANAGER_PROFILE = 60015, + QSHOT_STATUS = 60020, + COMPONENT_PREARM_STATUS = 60025, + AVSS_PRS_SYS_STATUS = 60050, + AVSS_DRONE_POSITION = 60051, + AVSS_DRONE_IMU = 60052, + AVSS_DRONE_OPERATION_MODE = 60053, + zVIDEO_STREAM_INFORMATION = 26900, } + + /// public enum ACCELCAL_VEHICLE_POS: int /*default*/ { @@ -703,6 +809,9 @@ public enum HEADING_TYPE: int /*default*/ /// | [Description("")] HEADING=1, + /// | + [Description("")] + DEFAULT=2, }; @@ -984,6 +1093,9 @@ public enum MAV_CMD: ushort /// Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera. |Camera trigger distance. 0 to stop triggering.| Camera shutter integration time. 0 to ignore| The minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore.| Total number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5).| Angle limits that the camera can be rolled to left and right of center.| Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.| Empty| [Description("Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera.")] OBLIQUE_SURVEY=260, + /// Enable the specified standard MAVLink mode. If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED. |The mode to set.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| + [Description("Enable the specified standard MAVLink mode. If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED. ")] + DO_SET_STANDARD_MODE=262, /// start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| [Description("start running a mission")] MISSION_START=300, @@ -1063,6 +1175,9 @@ 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, + /// Set system and component id. This allows moving of a system and all its components to a new system id, or moving a particular component to a new system/component id. Recipients must reject command addressed to broadcast system ID. |New system ID for target component(s). 0: ignore and reject command (broadcast system ID not allowed).| New component ID for target component(s). 0: ignore (component IDs don't change).| Reboot components after ID change. Any non-zero value triggers the reboot.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| + [Description(" Set system and component id. This allows moving of a system and all its components to a new system id, or moving a particular component to a new system/component id. Recipients must reject command addressed to broadcast system ID. ")] + DO_SET_SYS_CMP_ID=610, /// 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, @@ -1236,6 +1351,12 @@ public enum MAV_CMD: ushort /// Request forwarding of CAN packets from the given CAN bus to this interface. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages |Bus number (0 to disable forwarding, 1 for first bus, 2 for 2nd bus, 3 for 3rd bus).| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| [Description("Request forwarding of CAN packets from the given CAN bus to this interface. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages")] CAN_FORWARD=32000, + /// Mission command to reset Maximum Power Point Tracker (MPPT) |MPPT number| Empty| Empty| Empty| Empty| Empty| Empty| + [Description("Mission command to reset Maximum Power Point Tracker (MPPT)")] + RESET_MPPT=40001, + /// Mission command to perform a power cycle on payload |Complete power cycle| VISensor power cycle| Empty| Empty| Empty| Empty| Empty| + [Description("Mission command to perform a power cycle on payload")] + PAYLOAD_CONTROL=40002, /// A system wide power-off event has been initiated. |Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| [Description("A system wide power-off event has been initiated.")] POWER_OFF_INITIATED=42000, @@ -1325,9 +1446,48 @@ public enum MAV_CMD: ushort [Description("Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link.")] [hasLocation()] EXTERNAL_POSITION_ESTIMATE=43003, + /// Set an external estimate of wind direction and speed. This might be used to provide an initial wind estimate to the estimator (EKF) in the case where the vehicle is wind dead-reckoning, extending the time when operating without GPS before before position drift builds to an unsafe level. For this use case the command might reasonably be sent every few minutes when operating at altitude, and the value is cleared if the estimator resets itself. |Horizontal wind speed.| Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown.| Azimuth (relative to true north) from where the wind is blowing.| Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown.| Empty| Empty| Empty| + [Description("Set an external estimate of wind direction and speed. This might be used to provide an initial wind estimate to the estimator (EKF) in the case where the vehicle is wind dead-reckoning, extending the time when operating without GPS before before position drift builds to an unsafe level. For this use case the command might reasonably be sent every few minutes when operating at altitude, and the value is cleared if the estimator resets itself. ")] + EXTERNAL_WIND_ESTIMATE=43004, /// Provide a value for height above ground level. This can be used for things like fixed wing and VTOL landing. |Height above ground level.| estimated one standard deviation accuracy of the measurement. Set to NaN if not known.| Timeout for this data. The flight controller should only consider this data valid within the timeout window.| Empty| Empty| Empty| Empty| [Description("Provide a value for height above ground level. This can be used for things like fixed wing and VTOL landing.")] SET_HAGL=43005, + /// Command to a gimbal manager to control the gimbal tilt and pan angles. 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. A gimbal device is never to react to this command. |Pitch/tilt angle (positive: tilt up, NaN to be ignored).| Yaw/pan angle (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).| Pitch/tilt rate (positive: tilt up, NaN to be ignored).| Yaw/pan rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).| Gimbal device flags.| Gimbal manager flags.| Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). The client is copied into bits 8-15.| + [Description("Command to a gimbal manager to control the gimbal tilt and pan angles. 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. A gimbal device is never to react to this command.")] + STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW=60002, + /// Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. |Gimbal manager profile (0 = default).| Gimbal manager setup flags (0 = none).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.| + [Description("Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message.")] + [Obsolete] + STORM32_DO_GIMBAL_MANAGER_SETUP=60010, + /// Command to initiate gimbal actions. Usually performed by the gimbal device, but some can also be done by the gimbal manager. It is hence best to broadcast this command. |Gimbal action to initiate (0 = none).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Gimbal ID of the gimbal to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.| + [Description("Command to initiate gimbal actions. Usually performed by the gimbal device, but some can also be done by the gimbal manager. It is hence best to broadcast this command.")] + [Obsolete] + STORM32_DO_GIMBAL_ACTION=60011, + /// Command to set the shot manager mode. |Set shot mode.| Set shot state or command. The allowed values are specific to the selected shot mode.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| + [Description("Command to set the shot manager mode.")] + [Obsolete] + QSHOT_DO_CONFIGURE=60020, + /// AVSS defined command. Set PRS arm statuses. |PRS arm statuses| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Set PRS arm statuses.")] + PRS_SET_ARM=60050, + /// AVSS defined command. Gets PRS arm statuses |User defined| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Gets PRS arm statuses")] + PRS_GET_ARM=60051, + /// AVSS defined command. Get the PRS battery voltage in millivolts |User defined| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Get the PRS battery voltage in millivolts")] + PRS_GET_BATTERY=60052, + /// AVSS defined command. Get the PRS error statuses. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Get the PRS error statuses.")] + PRS_GET_ERR=60053, + /// AVSS defined command. Set the ATS arming altitude in meters. |ATS arming altitude| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Set the ATS arming altitude in meters.")] + PRS_SET_ARM_ALTI=60070, + /// AVSS defined command. Get the ATS arming altitude in meters. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Get the ATS arming altitude in meters.")] + PRS_GET_ARM_ALTI=60071, + /// AVSS defined command. Shuts down the PRS system. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| + [Description("AVSS defined command. Shuts down the PRS system.")] + PRS_SHUTDOWN=60072, }; @@ -2501,6 +2661,39 @@ public enum OSD_PARAM_CONFIG_ERROR: byte }; + /// + public enum GSM_LINK_TYPE: byte + { + /// no service | + [Description("no service")] + NONE=0, + /// link type unknown | + [Description("link type unknown")] + UNKNOWN=1, + /// 2G (GSM/GRPS/EDGE) link | + [Description("2G (GSM/GRPS/EDGE) link")] + _2G=2, + /// 3G link (WCDMA/HSDPA/HSPA) | + [Description("3G link (WCDMA/HSDPA/HSPA) ")] + _3G=3, + /// 4G link (LTE) | + [Description("4G link (LTE)")] + _4G=4, + + }; + + /// + public enum GSM_MODEM_TYPE: byte + { + /// not specified | + [Description("not specified")] + UNKNOWN=0, + /// HUAWEI LTE USB Stick E3372 | + [Description("HUAWEI LTE USB Stick E3372")] + HUAWEI_E3372=1, + + }; + /// These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. public enum FIRMWARE_VERSION_TYPE: int /*default*/ @@ -3117,7 +3310,7 @@ public enum GIMBAL_MANAGER_FLAGS: uint /// Gimbal device (low level) error flags (bitmap, 0 means no error) [Flags] - public enum GIMBAL_DEVICE_ERROR_FLAGS: uint + public enum GIMBAL_DEVICE_ERROR_FLAGS: ushort { /// Gimbal device is limited by hardware roll limit. | [Description("Gimbal device is limited by hardware roll limit.")] @@ -5933,366 +6126,180 @@ public enum SAFETY_SWITCH_STATE: int /*default*/ }; - /// State flags for ADS-B transponder dynamic report - public enum UAVIONIX_ADSB_OUT_DYNAMIC_STATE: ushort + /// Airspeed sensor flags + [Flags] + public enum AIRSPEED_SENSOR_FLAGS: byte { - /// | - [Description("")] - INTENT_CHANGE=1, - /// | - [Description("")] - AUTOPILOT_ENABLED=2, - /// | - [Description("")] - NICBARO_CROSSCHECKED=4, - /// | - [Description("")] - ON_GROUND=8, - /// | - [Description("")] - IDENT=16, + /// Airspeed sensor is unhealthy | + [Description("Airspeed sensor is unhealthy")] + AIRSPEED_SENSOR_UNHEALTHY=0, + /// True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. | + [Description("True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.")] + AIRSPEED_SENSOR_USING=1, }; - /// Transceiver RF control flags for ADS-B transponder dynamic reports - public enum UAVIONIX_ADSB_OUT_RF_SELECT: byte - { - /// | - [Description("")] - STANDBY=0, - /// | - [Description("")] - RX_ENABLED=1, - /// | - [Description("")] - TX_ENABLED=2, - - }; - - /// Status for ADS-B transponder dynamic input - public enum UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX: byte - { - /// | - [Description("")] - NONE_0=0, - /// | - [Description("")] - NONE_1=1, - /// | - [Description("")] - _2D=2, - /// | - [Description("")] - _3D=3, - /// | - [Description("")] - DGPS=4, - /// | - [Description("")] - RTK=5, + /// RADIO_RC_CHANNELS flags (bitmask). + [Flags] + public enum RADIO_RC_CHANNELS_FLAGS: ushort + { + /// Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. | + [Description("Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.")] + FAILSAFE=1, + /// Channel data may be out of date. This is set when the receiver is unable to validate incoming data from the transmitter and has therefore resent the last valid data it received. | + [Description("Channel data may be out of date. This is set when the receiver is unable to validate incoming data from the transmitter and has therefore resent the last valid data it received.")] + OUTDATED=2, + + }; + + /// Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a 'return' or 'RTL' mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. Modes may be set using MAV_CMD_DO_SET_STANDARD_MODE. + public enum MAV_STANDARD_MODE: byte + { + /// Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode. | + [Description("Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode. ")] + NON_STANDARD=0, + /// Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW ('VTOL') vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process). | + [Description("Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW ('VTOL') vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process). ")] + POSITION_HOLD=1, + /// Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW ('VTOL') vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process). | + [Description("Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW ('VTOL') vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process). ")] + ORBIT=2, + /// Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW ('VTOL') vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process). | + [Description("Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW ('VTOL') vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process). ")] + CRUISE=3, + /// Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW ('VTOL') vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process). | + [Description("Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW ('VTOL') vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process). ")] + ALTITUDE_HOLD=4, + /// Return home mode (auto). Automatic mode that returns vehicle to home via a safe flight path. It may also automatically land the vehicle (i.e. RTL). The precise flight path and landing behaviour depend on vehicle configuration and type. | + [Description("Return home mode (auto). Automatic mode that returns vehicle to home via a safe flight path. It may also automatically land the vehicle (i.e. RTL). The precise flight path and landing behaviour depend on vehicle configuration and type. ")] + RETURN_HOME=5, + /// Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path (rally point or mission defined landing) . It may also automatically land the vehicle. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. | + [Description("Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path (rally point or mission defined landing) . It may also automatically land the vehicle. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. ")] + SAFE_RECOVERY=6, + /// Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled. | + [Description("Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled. ")] + MISSION=7, + /// Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type. | + [Description("Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type. ")] + LAND=8, + /// Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type. | + [Description("Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type. ")] + TAKEOFF=9, + + }; + + /// Mode properties. + public enum MAV_MODE_PROPERTY: uint + { + /// If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users. | + [Description("If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users. ")] + ADVANCED=1, + /// If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe). | + [Description("If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe). ")] + NOT_USER_SELECTABLE=2, + + }; + + /// Flags indicating errors in a GPS receiver. + [Flags] + public enum GPS_SYSTEM_ERROR_FLAGS: uint + { + /// There are problems with incoming correction streams. | + [Description("There are problems with incoming correction streams.")] + GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS=1, + /// There are problems with the configuration. | + [Description("There are problems with the configuration.")] + GPS_SYSTEM_ERROR_CONFIGURATION=2, + /// There are problems with the software on the GPS receiver. | + [Description("There are problems with the software on the GPS receiver.")] + GPS_SYSTEM_ERROR_SOFTWARE=4, + /// There are problems with an antenna connected to the GPS receiver. | + [Description("There are problems with an antenna connected to the GPS receiver.")] + GPS_SYSTEM_ERROR_ANTENNA=8, + /// There are problems handling all incoming events. | + [Description("There are problems handling all incoming events.")] + GPS_SYSTEM_ERROR_EVENT_CONGESTION=16, + /// The GPS receiver CPU is overloaded. | + [Description("The GPS receiver CPU is overloaded.")] + GPS_SYSTEM_ERROR_CPU_OVERLOAD=32, + /// The GPS receiver is experiencing output congestion. | + [Description("The GPS receiver is experiencing output congestion.")] + GPS_SYSTEM_ERROR_OUTPUT_CONGESTION=64, + + }; + + /// Signal authentication state in a GPS receiver. + public enum GPS_AUTHENTICATION_STATE: byte + { + /// The GPS receiver does not provide GPS signal authentication info. | + [Description("The GPS receiver does not provide GPS signal authentication info.")] + UNKNOWN=0, + /// The GPS receiver is initializing signal authentication. | + [Description("The GPS receiver is initializing signal authentication.")] + INITIALIZING=1, + /// The GPS receiver encountered an error while initializing signal authentication. | + [Description("The GPS receiver encountered an error while initializing signal authentication.")] + ERROR=2, + /// The GPS receiver has correctly authenticated all signals. | + [Description("The GPS receiver has correctly authenticated all signals.")] + OK=3, + /// GPS signal authentication is disabled on the receiver. | + [Description("GPS signal authentication is disabled on the receiver.")] + DISABLED=4, }; - /// Status flags for ADS-B transponder dynamic output - public enum UAVIONIX_ADSB_RF_HEALTH: byte + /// Signal jamming state in a GPS receiver. + public enum GPS_JAMMING_STATE: byte { - /// | - [Description("")] - INITIALIZING=0, - /// | - [Description("")] + /// The GPS receiver does not provide GPS signal jamming info. | + [Description("The GPS receiver does not provide GPS signal jamming info.")] + UNKNOWN=0, + /// The GPS receiver detected no signal jamming. | + [Description("The GPS receiver detected no signal jamming.")] OK=1, - /// | - [Description("")] - FAIL_TX=2, - /// | - [Description("")] - FAIL_RX=16, - - }; - - /// Definitions for aircraft size - public enum UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE: byte - { - /// | - [Description("")] - NO_DATA=0, - /// | - [Description("")] - L15M_W23M=1, - /// | - [Description("")] - L25M_W28P5M=2, - /// | - [Description("")] - L25_34M=3, - /// | - [Description("")] - L35_33M=4, - /// | - [Description("")] - L35_38M=5, - /// | - [Description("")] - L45_39P5M=6, - /// | - [Description("")] - L45_45M=7, - /// | - [Description("")] - L55_45M=8, - /// | - [Description("")] - L55_52M=9, - /// | - [Description("")] - L65_59P5M=10, - /// | - [Description("")] - L65_67M=11, - /// | - [Description("")] - L75_W72P5M=12, - /// | - [Description("")] - L75_W80M=13, - /// | - [Description("")] - L85_W80M=14, - /// | - [Description("")] - L85_W90M=15, + /// The GPS receiver detected and mitigated signal jamming. | + [Description("The GPS receiver detected and mitigated signal jamming.")] + MITIGATED=2, + /// The GPS receiver detected signal jamming. | + [Description("The GPS receiver detected signal jamming.")] + DETECTED=3, }; - /// GPS lataral offset encoding - public enum UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT: byte + /// Signal spoofing state in a GPS receiver. + public enum GPS_SPOOFING_STATE: byte { - /// | - [Description("")] - NO_DATA=0, - /// | - [Description("")] - LEFT_2M=1, - /// | - [Description("")] - LEFT_4M=2, - /// | - [Description("")] - LEFT_6M=3, - /// | - [Description("")] - RIGHT_0M=4, - /// | - [Description("")] - RIGHT_2M=5, - /// | - [Description("")] - RIGHT_4M=6, - /// | - [Description("")] - RIGHT_6M=7, - - }; - - /// GPS longitudinal offset encoding - public enum UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON: byte - { - /// | - [Description("")] - NO_DATA=0, - /// | - [Description("")] - APPLIED_BY_SENSOR=1, - - }; - - /// Emergency status encoding - public enum UAVIONIX_ADSB_EMERGENCY_STATUS: byte - { - /// | - [Description("")] - UAVIONIX_ADSB_OUT_NO_EMERGENCY=0, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY=1, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY=2, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY=3, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY=4, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY=5, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY=6, - /// | - [Description("")] - UAVIONIX_ADSB_OUT_RESERVED=7, - - }; - - /// State flags for ADS-B transponder dynamic report - public enum UAVIONIX_ADSB_OUT_CONTROL_STATE: byte - { - /// | - [Description("")] - EXTERNAL_BARO_CROSSCHECKED=1, - /// | - [Description("")] - ON_GROUND=4, - /// | - [Description("")] - IDENT_BUTTON_ACTIVE=8, - /// | - [Description("")] - MODE_A_ENABLED=16, - /// | - [Description("")] - MODE_C_ENABLED=32, - /// | - [Description("")] - MODE_S_ENABLED=64, - /// | - [Description("")] - _1090ES_TX_ENABLED=128, - - }; - - /// State flags for X-Bit and reserved fields. - public enum UAVIONIX_ADSB_XBIT: byte - { - /// | - [Description("")] - ENABLED=128, - - }; - - /// State flags for ADS-B transponder status report - public enum UAVIONIX_ADSB_OUT_STATUS_STATE: byte - { - /// | - [Description("")] - ON_GROUND=1, - /// | - [Description("")] - INTERROGATED_SINCE_LAST=2, - /// | - [Description("")] - XBIT_ENABLED=4, - /// | - [Description("")] - IDENT_ACTIVE=8, - /// | - [Description("")] - MODE_A_ENABLED=16, - /// | - [Description("")] - MODE_C_ENABLED=32, - /// | - [Description("")] - MODE_S_ENABLED=64, - /// | - [Description("")] - _1090ES_TX_ENABLED=128, - - }; - - /// State flags for ADS-B transponder status report - public enum UAVIONIX_ADSB_OUT_STATUS_NIC_NACP: byte - { - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_20_NM=1, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_8_NM=2, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_4_NM=3, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_2_NM=4, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_1_NM=5, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_0_3_NM=6, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_0_2_NM=7, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_0_1_NM=8, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_75_M=9, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_25_M=10, - /// | - [Description("")] - UAVIONIX_ADSB_NIC_CR_7_5_M=11, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_10_NM=16, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_4_NM=32, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_2_NM=48, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_1_NM=64, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_0_5_NM=80, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_0_3_NM=96, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_0_1_NM=112, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_0_05_NM=128, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_30_M=144, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_10_M=160, - /// | - [Description("")] - UAVIONIX_ADSB_NACP_EPU_3_M=176, + /// The GPS receiver does not provide GPS signal spoofing info. | + [Description("The GPS receiver does not provide GPS signal spoofing info.")] + UNKNOWN=0, + /// The GPS receiver detected no signal spoofing. | + [Description("The GPS receiver detected no signal spoofing.")] + OK=1, + /// The GPS receiver detected and mitigated signal spoofing. | + [Description("The GPS receiver detected and mitigated signal spoofing.")] + MITIGATED=2, + /// The GPS receiver detected signal spoofing but still has a fix. | + [Description("The GPS receiver detected signal spoofing but still has a fix.")] + DETECTED=3, }; - /// State flags for ADS-B transponder fault report - public enum UAVIONIX_ADSB_OUT_STATUS_FAULT: byte + /// State of RAIM processing. + public enum GPS_RAIM_STATE: byte { - /// | - [Description("")] - STATUS_MESSAGE_UNAVAIL=8, - /// | - [Description("")] - GPS_NO_POS=16, - /// | - [Description("")] - GPS_UNAVAIL=32, - /// | - [Description("")] - TX_SYSTEM_FAIL=64, - /// | - [Description("")] - MAINT_REQ=128, + /// RAIM capability is unknown. | + [Description("RAIM capability is unknown.")] + UNKNOWN=0, + /// RAIM is disabled. | + [Description("RAIM is disabled.")] + DISABLED=1, + /// RAIM integrity check was successful. | + [Description("RAIM integrity check was successful.")] + OK=2, + /// RAIM integrity check failed. | + [Description("RAIM integrity check failed.")] + FAILED=3, }; @@ -6337,21 +6344,6 @@ 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 { @@ -7059,452 +7051,1455 @@ public enum MAV_COMPONENT: int /*default*/ }; - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. - public struct mavlink_sensor_offsets_t + + + + + /// Available autopilot modes for ualberta uav + public enum UALBERTA_AUTOPILOT_MODE: int /*default*/ { - /// packet ordered constructor - public mavlink_sensor_offsets_t(float mag_declination,int raw_press,int raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z,short mag_ofs_x,short mag_ofs_y,short mag_ofs_z) - { - this.mag_declination = mag_declination; - this.raw_press = raw_press; - this.raw_temp = raw_temp; - this.gyro_cal_x = gyro_cal_x; - this.gyro_cal_y = gyro_cal_y; - this.gyro_cal_z = gyro_cal_z; - this.accel_cal_x = accel_cal_x; - this.accel_cal_y = accel_cal_y; - this.accel_cal_z = accel_cal_z; - this.mag_ofs_x = mag_ofs_x; - this.mag_ofs_y = mag_ofs_y; - this.mag_ofs_z = mag_ofs_z; - - } - - /// packet xml order - public static mavlink_sensor_offsets_t PopulateXMLOrder(short mag_ofs_x,short mag_ofs_y,short mag_ofs_z,float mag_declination,int raw_press,int raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z) - { - var msg = new mavlink_sensor_offsets_t(); - - msg.mag_ofs_x = mag_ofs_x; - msg.mag_ofs_y = mag_ofs_y; - msg.mag_ofs_z = mag_ofs_z; - msg.mag_declination = mag_declination; - msg.raw_press = raw_press; - msg.raw_temp = raw_temp; - msg.gyro_cal_x = gyro_cal_x; - msg.gyro_cal_y = gyro_cal_y; - msg.gyro_cal_z = gyro_cal_z; - msg.accel_cal_x = accel_cal_x; - msg.accel_cal_y = accel_cal_y; - msg.accel_cal_z = accel_cal_z; - - return msg; - } + /// Raw input pulse widts sent to output | + [Description("Raw input pulse widts sent to output")] + MODE_MANUAL_DIRECT=1, + /// Inputs are normalized using calibration, the converted back to raw pulse widths for output | + [Description("Inputs are normalized using calibration, the converted back to raw pulse widths for output")] + MODE_MANUAL_SCALED=2, + /// dfsdfs | + [Description(" dfsdfs")] + MODE_AUTO_PID_ATT=3, + /// dfsfds | + [Description(" dfsfds")] + MODE_AUTO_PID_VEL=4, + /// dfsdfsdfs | + [Description(" dfsdfsdfs")] + MODE_AUTO_PID_POS=5, - - /// Magnetic declination. [rad] - [Units("[rad]")] - [Description("Magnetic declination.")] - //[FieldOffset(0)] - public float mag_declination; - - /// Raw pressure from barometer. - [Units("")] - [Description("Raw pressure from barometer.")] - //[FieldOffset(4)] - public int raw_press; - - /// Raw temperature from barometer. - [Units("")] - [Description("Raw temperature from barometer.")] - //[FieldOffset(8)] - public int raw_temp; - - /// Gyro X calibration. - [Units("")] - [Description("Gyro X calibration.")] - //[FieldOffset(12)] - public float gyro_cal_x; - - /// Gyro Y calibration. - [Units("")] - [Description("Gyro Y calibration.")] - //[FieldOffset(16)] - public float gyro_cal_y; - - /// Gyro Z calibration. - [Units("")] - [Description("Gyro Z calibration.")] - //[FieldOffset(20)] - public float gyro_cal_z; - - /// Accel X calibration. - [Units("")] - [Description("Accel X calibration.")] - //[FieldOffset(24)] - public float accel_cal_x; - - /// Accel Y calibration. - [Units("")] - [Description("Accel Y calibration.")] - //[FieldOffset(28)] - public float accel_cal_y; - - /// Accel Z calibration. - [Units("")] - [Description("Accel Z calibration.")] - //[FieldOffset(32)] - public float accel_cal_z; - - /// Magnetometer X offset. - [Units("")] - [Description("Magnetometer X offset.")] - //[FieldOffset(36)] - public short mag_ofs_x; - - /// Magnetometer Y offset. - [Units("")] - [Description("Magnetometer Y offset.")] - //[FieldOffset(38)] - public short mag_ofs_y; - - /// Magnetometer Z offset. - [Units("")] - [Description("Magnetometer Z offset.")] - //[FieldOffset(40)] - public short mag_ofs_z; }; - - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// Set the magnetometer offsets - public struct mavlink_set_mag_offsets_t + + /// Navigation filter mode + public enum UALBERTA_NAV_MODE: int /*default*/ { - /// packet ordered constructor - public mavlink_set_mag_offsets_t(short mag_ofs_x,short mag_ofs_y,short mag_ofs_z,byte target_system,byte target_component) - { - this.mag_ofs_x = mag_ofs_x; - this.mag_ofs_y = mag_ofs_y; - this.mag_ofs_z = mag_ofs_z; - this.target_system = target_system; - this.target_component = target_component; - - } - - /// packet xml order - public static mavlink_set_mag_offsets_t PopulateXMLOrder(byte target_system,byte target_component,short mag_ofs_x,short mag_ofs_y,short mag_ofs_z) - { - var msg = new mavlink_set_mag_offsets_t(); - - msg.target_system = target_system; - msg.target_component = target_component; - msg.mag_ofs_x = mag_ofs_x; - msg.mag_ofs_y = mag_ofs_y; - msg.mag_ofs_z = mag_ofs_z; - - return msg; - } + /// | + [Description("")] + AHRS_INIT=1, + /// AHRS mode | + [Description("AHRS mode")] + AHRS=2, + /// INS/GPS initialization mode | + [Description("INS/GPS initialization mode")] + INS_GPS_INIT=3, + /// INS/GPS mode | + [Description("INS/GPS mode")] + INS_GPS=4, - - /// Magnetometer X offset. - [Units("")] - [Description("Magnetometer X offset.")] - //[FieldOffset(0)] - public short mag_ofs_x; - - /// Magnetometer Y offset. - [Units("")] - [Description("Magnetometer Y offset.")] - //[FieldOffset(2)] - public short mag_ofs_y; - - /// Magnetometer Z offset. - [Units("")] - [Description("Magnetometer Z offset.")] - //[FieldOffset(4)] - public short mag_ofs_z; - - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(6)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(7)] - public byte target_component; }; - - /// extensions_start 2 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// State of autopilot RAM. - public struct mavlink_meminfo_t + /// Mode currently commanded by pilot + public enum UALBERTA_PILOT_MODE: int /*default*/ { - /// packet ordered constructor - public mavlink_meminfo_t(ushort brkval,ushort freemem,uint freemem32) - { - this.brkval = brkval; - this.freemem = freemem; - this.freemem32 = freemem32; - - } - - /// packet xml order - public static mavlink_meminfo_t PopulateXMLOrder(ushort brkval,ushort freemem,uint freemem32) - { - var msg = new mavlink_meminfo_t(); - - msg.brkval = brkval; - msg.freemem = freemem; - msg.freemem32 = freemem32; - - return msg; - } + /// sdf | + [Description(" sdf")] + PILOT_MANUAL=1, + /// dfs | + [Description(" dfs")] + PILOT_AUTO=2, + /// Rotomotion mode | + [Description(" Rotomotion mode ")] + PILOT_ROTO=3, - - /// Heap top. - [Units("")] - [Description("Heap top.")] - //[FieldOffset(0)] - public ushort brkval; - - /// Free memory. [bytes] - [Units("[bytes]")] - [Description("Free memory.")] - //[FieldOffset(2)] - public ushort freemem; - - /// Free memory (32 bit). [bytes] - [Units("[bytes]")] - [Description("Free memory (32 bit).")] - //[FieldOffset(4)] - public uint freemem32; }; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - /// Raw ADC output. - public struct mavlink_ap_adc_t + + /// State flags for ADS-B transponder dynamic report + public enum UAVIONIX_ADSB_OUT_DYNAMIC_STATE: ushort { - /// packet ordered constructor - public mavlink_ap_adc_t(ushort adc1,ushort adc2,ushort adc3,ushort adc4,ushort adc5,ushort adc6) - { - this.adc1 = adc1; - this.adc2 = adc2; - this.adc3 = adc3; - this.adc4 = adc4; - this.adc5 = adc5; - this.adc6 = adc6; - - } - - /// packet xml order - public static mavlink_ap_adc_t PopulateXMLOrder(ushort adc1,ushort adc2,ushort adc3,ushort adc4,ushort adc5,ushort adc6) - { - var msg = new mavlink_ap_adc_t(); - - msg.adc1 = adc1; - msg.adc2 = adc2; - msg.adc3 = adc3; - msg.adc4 = adc4; - msg.adc5 = adc5; - msg.adc6 = adc6; - - return msg; - } + /// | + [Description("")] + INTENT_CHANGE=1, + /// | + [Description("")] + AUTOPILOT_ENABLED=2, + /// | + [Description("")] + NICBARO_CROSSCHECKED=4, + /// | + [Description("")] + ON_GROUND=8, + /// | + [Description("")] + IDENT=16, - - /// ADC output 1. - [Units("")] - [Description("ADC output 1.")] - //[FieldOffset(0)] - public ushort adc1; - - /// ADC output 2. - [Units("")] - [Description("ADC output 2.")] - //[FieldOffset(2)] - public ushort adc2; - - /// ADC output 3. - [Units("")] - [Description("ADC output 3.")] - //[FieldOffset(4)] - public ushort adc3; - - /// ADC output 4. - [Units("")] - [Description("ADC output 4.")] - //[FieldOffset(6)] - public ushort adc4; - - /// ADC output 5. - [Units("")] - [Description("ADC output 5.")] - //[FieldOffset(8)] - public ushort adc5; - - /// ADC output 6. - [Units("")] - [Description("ADC output 6.")] - //[FieldOffset(10)] - public ushort adc6; }; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - /// Configure on-board Camera Control System. - public struct mavlink_digicam_configure_t + /// Transceiver RF control flags for ADS-B transponder dynamic reports + public enum UAVIONIX_ADSB_OUT_RF_SELECT: byte { - /// packet ordered constructor - public mavlink_digicam_configure_t(float extra_value,ushort shutter_speed,byte target_system,byte target_component,byte mode,byte aperture,byte iso,byte exposure_type,byte command_id,byte engine_cut_off,byte extra_param) - { - this.extra_value = extra_value; - this.shutter_speed = shutter_speed; - this.target_system = target_system; - this.target_component = target_component; - this.mode = mode; - this.aperture = aperture; - this.iso = iso; - this.exposure_type = exposure_type; - this.command_id = command_id; - this.engine_cut_off = engine_cut_off; - this.extra_param = extra_param; - - } + /// | + [Description("")] + STANDBY=0, + /// | + [Description("")] + RX_ENABLED=1, + /// | + [Description("")] + TX_ENABLED=2, - /// packet xml order - public static mavlink_digicam_configure_t PopulateXMLOrder(byte target_system,byte target_component,byte mode,ushort shutter_speed,byte aperture,byte iso,byte exposure_type,byte command_id,byte engine_cut_off,byte extra_param,float extra_value) - { - var msg = new mavlink_digicam_configure_t(); - - msg.target_system = target_system; - msg.target_component = target_component; - msg.mode = mode; - msg.shutter_speed = shutter_speed; - msg.aperture = aperture; - msg.iso = iso; - msg.exposure_type = exposure_type; - msg.command_id = command_id; - msg.engine_cut_off = engine_cut_off; - msg.extra_param = extra_param; - msg.extra_value = extra_value; - - return msg; - } + }; + + /// Status for ADS-B transponder dynamic input + public enum UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX: byte + { + /// | + [Description("")] + NONE_0=0, + /// | + [Description("")] + NONE_1=1, + /// | + [Description("")] + _2D=2, + /// | + [Description("")] + _3D=3, + /// | + [Description("")] + DGPS=4, + /// | + [Description("")] + RTK=5, - - /// Correspondent value to given extra_param. - [Units("")] - [Description("Correspondent value to given extra_param.")] - //[FieldOffset(0)] - public float extra_value; - - /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore). - [Units("")] - [Description("Divisor number //e.g. 1000 means 1/1000 (0 means ignore).")] - //[FieldOffset(4)] - public ushort shutter_speed; - - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(6)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(7)] - public byte target_component; - - /// Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore). - [Units("")] - [Description("Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).")] - //[FieldOffset(8)] - public byte mode; - - /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore). - [Units("")] - [Description("F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).")] - //[FieldOffset(9)] - public byte aperture; - - /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore). - [Units("")] - [Description("ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).")] - //[FieldOffset(10)] - public byte iso; - - /// Exposure type enumeration from 1 to N (0 means ignore). - [Units("")] - [Description("Exposure type enumeration from 1 to N (0 means ignore).")] - //[FieldOffset(11)] - public byte exposure_type; - - /// Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once. - [Units("")] - [Description("Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.")] - //[FieldOffset(12)] - public byte command_id; - - /// Main engine cut-off time before camera trigger (0 means no cut-off). [ds] - [Units("[ds]")] - [Description("Main engine cut-off time before camera trigger (0 means no cut-off).")] - //[FieldOffset(13)] - public byte engine_cut_off; - - /// Extra parameters enumeration (0 means ignore). - [Units("")] - [Description("Extra parameters enumeration (0 means ignore).")] - //[FieldOffset(14)] - public byte extra_param; }; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] - /// Control on-board Camera Control System to take shots. - public struct mavlink_digicam_control_t + /// Status flags for ADS-B transponder dynamic output + public enum UAVIONIX_ADSB_RF_HEALTH: byte { - /// packet ordered constructor - public mavlink_digicam_control_t(float extra_value,byte target_system,byte target_component,byte session,byte zoom_pos,sbyte zoom_step,byte focus_lock,byte shot,byte command_id,byte extra_param) - { - this.extra_value = extra_value; - this.target_system = target_system; - this.target_component = target_component; - this.session = session; - this.zoom_pos = zoom_pos; - this.zoom_step = zoom_step; - this.focus_lock = focus_lock; - this.shot = shot; - this.command_id = command_id; - this.extra_param = extra_param; - - } + /// | + [Description("")] + INITIALIZING=0, + /// | + [Description("")] + OK=1, + /// | + [Description("")] + FAIL_TX=2, + /// | + [Description("")] + FAIL_RX=16, - /// packet xml order - public static mavlink_digicam_control_t PopulateXMLOrder(byte target_system,byte target_component,byte session,byte zoom_pos,sbyte zoom_step,byte focus_lock,byte shot,byte command_id,byte extra_param,float extra_value) - { - var msg = new mavlink_digicam_control_t(); - - msg.target_system = target_system; - msg.target_component = target_component; - msg.session = session; - msg.zoom_pos = zoom_pos; - msg.zoom_step = zoom_step; - msg.focus_lock = focus_lock; - msg.shot = shot; - msg.command_id = command_id; + }; + + /// Definitions for aircraft size + public enum UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE: byte + { + /// | + [Description("")] + NO_DATA=0, + /// | + [Description("")] + L15M_W23M=1, + /// | + [Description("")] + L25M_W28P5M=2, + /// | + [Description("")] + L25_34M=3, + /// | + [Description("")] + L35_33M=4, + /// | + [Description("")] + L35_38M=5, + /// | + [Description("")] + L45_39P5M=6, + /// | + [Description("")] + L45_45M=7, + /// | + [Description("")] + L55_45M=8, + /// | + [Description("")] + L55_52M=9, + /// | + [Description("")] + L65_59P5M=10, + /// | + [Description("")] + L65_67M=11, + /// | + [Description("")] + L75_W72P5M=12, + /// | + [Description("")] + L75_W80M=13, + /// | + [Description("")] + L85_W80M=14, + /// | + [Description("")] + L85_W90M=15, + + }; + + /// GPS lataral offset encoding + public enum UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT: byte + { + /// | + [Description("")] + NO_DATA=0, + /// | + [Description("")] + LEFT_2M=1, + /// | + [Description("")] + LEFT_4M=2, + /// | + [Description("")] + LEFT_6M=3, + /// | + [Description("")] + RIGHT_0M=4, + /// | + [Description("")] + RIGHT_2M=5, + /// | + [Description("")] + RIGHT_4M=6, + /// | + [Description("")] + RIGHT_6M=7, + + }; + + /// GPS longitudinal offset encoding + public enum UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON: byte + { + /// | + [Description("")] + NO_DATA=0, + /// | + [Description("")] + APPLIED_BY_SENSOR=1, + + }; + + /// Emergency status encoding + public enum UAVIONIX_ADSB_EMERGENCY_STATUS: byte + { + /// | + [Description("")] + UAVIONIX_ADSB_OUT_NO_EMERGENCY=0, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY=1, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY=2, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY=3, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY=4, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY=5, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY=6, + /// | + [Description("")] + UAVIONIX_ADSB_OUT_RESERVED=7, + + }; + + /// State flags for ADS-B transponder dynamic report + public enum UAVIONIX_ADSB_OUT_CONTROL_STATE: byte + { + /// | + [Description("")] + EXTERNAL_BARO_CROSSCHECKED=1, + /// | + [Description("")] + ON_GROUND=4, + /// | + [Description("")] + IDENT_BUTTON_ACTIVE=8, + /// | + [Description("")] + MODE_A_ENABLED=16, + /// | + [Description("")] + MODE_C_ENABLED=32, + /// | + [Description("")] + MODE_S_ENABLED=64, + /// | + [Description("")] + _1090ES_TX_ENABLED=128, + + }; + + /// State flags for X-Bit and reserved fields. + public enum UAVIONIX_ADSB_XBIT: byte + { + /// | + [Description("")] + ENABLED=128, + + }; + + /// State flags for ADS-B transponder status report + public enum UAVIONIX_ADSB_OUT_STATUS_STATE: byte + { + /// | + [Description("")] + ON_GROUND=1, + /// | + [Description("")] + INTERROGATED_SINCE_LAST=2, + /// | + [Description("")] + XBIT_ENABLED=4, + /// | + [Description("")] + IDENT_ACTIVE=8, + /// | + [Description("")] + MODE_A_ENABLED=16, + /// | + [Description("")] + MODE_C_ENABLED=32, + /// | + [Description("")] + MODE_S_ENABLED=64, + /// | + [Description("")] + _1090ES_TX_ENABLED=128, + + }; + + /// State flags for ADS-B transponder status report + public enum UAVIONIX_ADSB_OUT_STATUS_NIC_NACP: byte + { + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_20_NM=1, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_8_NM=2, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_4_NM=3, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_2_NM=4, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_1_NM=5, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_0_3_NM=6, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_0_2_NM=7, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_0_1_NM=8, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_75_M=9, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_25_M=10, + /// | + [Description("")] + UAVIONIX_ADSB_NIC_CR_7_5_M=11, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_10_NM=16, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_4_NM=32, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_2_NM=48, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_1_NM=64, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_0_5_NM=80, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_0_3_NM=96, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_0_1_NM=112, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_0_05_NM=128, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_30_M=144, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_10_M=160, + /// | + [Description("")] + UAVIONIX_ADSB_NACP_EPU_3_M=176, + + }; + + /// State flags for ADS-B transponder fault report + public enum UAVIONIX_ADSB_OUT_STATUS_FAULT: byte + { + /// | + [Description("")] + STATUS_MESSAGE_UNAVAIL=8, + /// | + [Description("")] + GPS_NO_POS=16, + /// | + [Description("")] + GPS_UNAVAIL=32, + /// | + [Description("")] + TX_SYSTEM_FAIL=64, + /// | + [Description("")] + MAINT_REQ=128, + + }; + + + + /// + public enum MAV_STORM32_TUNNEL_PAYLOAD_TYPE: int /*default*/ + { + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_CH1_IN=200, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_CH1_OUT=201, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_CH2_IN=202, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_CH2_OUT=203, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_CH3_IN=204, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_CH3_OUT=205, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_RESERVED6=206, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_RESERVED7=207, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_RESERVED8=208, + /// Registered for STorM32 gimbal controller. | + [Description("Registered for STorM32 gimbal controller.")] + STORM32_RESERVED9=209, + + }; + + /// STorM32 gimbal prearm check flags. + [Flags] + public enum MAV_STORM32_GIMBAL_PREARM_FLAGS: int /*default*/ + { + /// STorM32 gimbal is in normal state. | + [Description("STorM32 gimbal is in normal state.")] + IS_NORMAL=1, + /// The IMUs are healthy and working normally. | + [Description("The IMUs are healthy and working normally.")] + IMUS_WORKING=2, + /// The motors are active and working normally. | + [Description("The motors are active and working normally.")] + MOTORS_WORKING=4, + /// The encoders are healthy and working normally. | + [Description("The encoders are healthy and working normally.")] + ENCODERS_WORKING=8, + /// A battery voltage is applied and is in range. | + [Description("A battery voltage is applied and is in range.")] + VOLTAGE_OK=16, + /// ???. | + [Description("???.")] + VIRTUALCHANNELS_RECEIVING=32, + /// Mavlink messages are being received. | + [Description("Mavlink messages are being received.")] + MAVLINK_RECEIVING=64, + /// The STorM32Link data indicates QFix. | + [Description("The STorM32Link data indicates QFix.")] + STORM32LINK_QFIX=128, + /// The STorM32Link is working. | + [Description("The STorM32Link is working.")] + STORM32LINK_WORKING=256, + /// The camera has been found and is connected. | + [Description("The camera has been found and is connected.")] + CAMERA_CONNECTED=512, + /// The signal on the AUX0 input pin is low. | + [Description("The signal on the AUX0 input pin is low.")] + AUX0_LOW=1024, + /// The signal on the AUX1 input pin is low. | + [Description("The signal on the AUX1 input pin is low.")] + AUX1_LOW=2048, + /// The NTLogger is working normally. | + [Description("The NTLogger is working normally.")] + NTLOGGER_WORKING=4096, + + }; + + /// STorM32 camera prearm check flags. + [Flags] + public enum MAV_STORM32_CAMERA_PREARM_FLAGS: int /*default*/ + { + /// The camera has been found and is connected. | + [Description("The camera has been found and is connected.")] + CONNECTED=1, + + }; + + /// Gimbal device capability flags. + [Flags] + public enum MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS: uint + { + /// 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. Can also be used to reset the gimbal's orientation. | + [Description("Gimbal device supports a horizontal, forward looking position, stabilized. Can also be used to reset the gimbal's orientation.")] + 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.")] + HAS_ROLL_FOLLOW=8, + /// Gimbal device supports locking to an roll angle (generally that's the default). | + [Description("Gimbal device supports locking to an roll angle (generally that's the default).")] + 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.")] + HAS_PITCH_FOLLOW=64, + /// Gimbal device supports locking to an pitch angle (generally that's the default). | + [Description("Gimbal device supports locking to an pitch angle (generally that's the default).")] + 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).")] + HAS_YAW_FOLLOW=512, + /// Gimbal device supports locking to a heading angle. | + [Description("Gimbal device supports locking to a heading angle.")] + HAS_YAW_LOCK=1024, + /// Gimbal device supports yawing/panning infinitely (e.g. using a slip ring). | + [Description("Gimbal device supports yawing/panning infinitely (e.g. using a slip ring).")] + HAS_INFINITE_YAW=2048, + /// Gimbal device supports absolute yaw angles (this usually requires support by an autopilot, and can be dynamic, i.e., go on and off during runtime). | + [Description("Gimbal device supports absolute yaw angles (this usually requires support by an autopilot, and can be dynamic, i.e., go on and off during runtime).")] + HAS_ABSOLUTE_YAW=65536, + /// Gimbal device supports control via an RC input signal. | + [Description("Gimbal device supports control via an RC input signal.")] + HAS_RC=131072, + + }; + + /// Flags for gimbal device operation. Used for setting and reporting, unless specified otherwise. Settings which are in violation of the capability flags are ignored by the gimbal device. + [Flags] + public enum MAV_STORM32_GIMBAL_DEVICE_FLAGS: ushort + { + /// Retracted safe position (no stabilization), takes presedence over NEUTRAL flag. If supported by the gimbal, the angles in the retracted position can be set in addition. | + [Description("Retracted safe position (no stabilization), takes presedence over NEUTRAL flag. If supported by the gimbal, the angles in the retracted position can be set in addition.")] + RETRACT=1, + /// Neutral position (horizontal, forward looking, with stabiliziation). | + [Description("Neutral position (horizontal, forward looking, with stabiliziation).")] + NEUTRAL=2, + /// Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default. | + [Description("Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default.")] + 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.")] + PITCH_LOCK=8, + /// Lock yaw angle to absolute angle relative to earth (not relative to drone). When the YAW_ABSOLUTE flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it 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 earth (not relative to drone). When the YAW_ABSOLUTE flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle).")] + YAW_LOCK=16, + /// Gimbal device can accept absolute yaw angle input. This flag cannot be set, is only for reporting (attempts to set it are rejected by the gimbal device). | + [Description("Gimbal device can accept absolute yaw angle input. This flag cannot be set, is only for reporting (attempts to set it are rejected by the gimbal device).")] + CAN_ACCEPT_YAW_ABSOLUTE=256, + /// Yaw angle is absolute (is only accepted if CAN_ACCEPT_YAW_ABSOLUTE is set). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). | + [Description("Yaw angle is absolute (is only accepted if CAN_ACCEPT_YAW_ABSOLUTE is set). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle).")] + YAW_ABSOLUTE=512, + /// RC control. The RC input signal fed to the gimbal device exclusively controls the gimbal's orientation. Overrides RC_MIXED flag if that is also set. | + [Description("RC control. The RC input signal fed to the gimbal device exclusively controls the gimbal's orientation. Overrides RC_MIXED flag if that is also set.")] + RC_EXCLUSIVE=1024, + /// RC control. The RC input signal fed to the gimbal device is mixed into the gimbal's orientation. Is overriden by RC_EXCLUSIVE flag if that is also set. | + [Description("RC control. The RC input signal fed to the gimbal device is mixed into the gimbal's orientation. Is overriden by RC_EXCLUSIVE flag if that is also set.")] + RC_MIXED=2048, + /// UINT16_MAX = ignore. | + [Description("UINT16_MAX = ignore.")] + NONE=65535, + + }; + + /// Gimbal device error and condition flags (0 means no error or other condition). + [Flags] + public enum MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS: int /*default*/ + { + /// Gimbal device is limited by hardware roll limit. | + [Description("Gimbal device is limited by hardware roll limit.")] + AT_ROLL_LIMIT=1, + /// Gimbal device is limited by hardware pitch limit. | + [Description("Gimbal device is limited by hardware pitch limit.")] + AT_PITCH_LIMIT=2, + /// Gimbal device is limited by hardware yaw limit. | + [Description("Gimbal device is limited by hardware yaw limit.")] + AT_YAW_LIMIT=4, + /// There is an error with the gimbal device's encoders. | + [Description("There is an error with the gimbal device's encoders.")] + ENCODER_ERROR=8, + /// There is an error with the gimbal device's power source. | + [Description("There is an error with the gimbal device's power source.")] + POWER_ERROR=16, + /// There is an error with the gimbal device's motors. | + [Description("There is an error with the gimbal device's motors.")] + MOTOR_ERROR=32, + /// There is an error with the gimbal device's software. | + [Description("There is an error with the gimbal device's software.")] + SOFTWARE_ERROR=64, + /// There is an error with the gimbal device's communication. | + [Description("There is an error with the gimbal device's communication.")] + COMMS_ERROR=128, + /// Gimbal device is currently calibrating (not an error). | + [Description("Gimbal device is currently calibrating (not an error).")] + CALIBRATION_RUNNING=256, + /// Gimbal device is not assigned to a gimbal manager (not an error). | + [Description("Gimbal device is not assigned to a gimbal manager (not an error).")] + NO_MANAGER=32768, + + }; + + /// Gimbal manager capability flags. + [Flags] + public enum MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS: uint + { + /// The gimbal manager supports several profiles. | + [Description("The gimbal manager supports several profiles.")] + HAS_PROFILES=1, + /// The gimbal manager supports changing the gimbal manager during run time, i.e. can be enabled/disabled. | + [Description("The gimbal manager supports changing the gimbal manager during run time, i.e. can be enabled/disabled.")] + SUPPORTS_CHANGE=2, + + }; + + /// Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting is accepted by the gimbal manger, is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + [Flags] + public enum MAV_STORM32_GIMBAL_MANAGER_FLAGS: ushort + { + /// 0 = ignore. | + [Description("0 = ignore.")] + NONE=0, + /// Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive. | + [Description("Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive.")] + RC_ACTIVE=1, + /// Request to set onboard/companion computer client to active, or report this client is active. | + [Description("Request to set onboard/companion computer client to active, or report this client is active.")] + CLIENT_ONBOARD_ACTIVE=2, + /// Request to set autopliot client to active, or report this client is active. | + [Description("Request to set autopliot client to active, or report this client is active.")] + CLIENT_AUTOPILOT_ACTIVE=4, + /// Request to set GCS client to active, or report this client is active. | + [Description("Request to set GCS client to active, or report this client is active.")] + CLIENT_GCS_ACTIVE=8, + /// Request to set camera client to active, or report this client is active. | + [Description("Request to set camera client to active, or report this client is active.")] + CLIENT_CAMERA_ACTIVE=16, + /// Request to set GCS2 client to active, or report this client is active. | + [Description("Request to set GCS2 client to active, or report this client is active.")] + CLIENT_GCS2_ACTIVE=32, + /// Request to set camera2 client to active, or report this client is active. | + [Description("Request to set camera2 client to active, or report this client is active.")] + CLIENT_CAMERA2_ACTIVE=64, + /// Request to set custom client to active, or report this client is active. | + [Description("Request to set custom client to active, or report this client is active.")] + CLIENT_CUSTOM_ACTIVE=128, + /// Request to set custom2 client to active, or report this client is active. | + [Description("Request to set custom2 client to active, or report this client is active.")] + CLIENT_CUSTOM2_ACTIVE=256, + /// Request supervision. This flag is only for setting, it is not reported. | + [Description("Request supervision. This flag is only for setting, it is not reported.")] + SET_SUPERVISON=512, + /// Release supervision. This flag is only for setting, it is not reported. | + [Description("Release supervision. This flag is only for setting, it is not reported.")] + SET_RELEASE=1024, + + }; + + /// Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2. + public enum MAV_STORM32_GIMBAL_MANAGER_CLIENT: byte + { + /// For convenience. | + [Description("For convenience.")] + NONE=0, + /// This is the onboard/companion computer client. | + [Description("This is the onboard/companion computer client.")] + ONBOARD=1, + /// This is the autopilot client. | + [Description("This is the autopilot client.")] + AUTOPILOT=2, + /// This is the GCS client. | + [Description("This is the GCS client.")] + GCS=3, + /// This is the camera client. | + [Description("This is the camera client.")] + CAMERA=4, + /// This is the GCS2 client. | + [Description("This is the GCS2 client.")] + GCS2=5, + /// This is the camera2 client. | + [Description("This is the camera2 client.")] + CAMERA2=6, + /// This is the custom client. | + [Description("This is the custom client.")] + CUSTOM=7, + /// This is the custom2 client. | + [Description("This is the custom2 client.")] + CUSTOM2=8, + + }; + + /// Flags for gimbal manager set up. Used for setting and reporting, unless specified otherwise. + [Flags] + public enum MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS: int /*default*/ + { + /// Enable gimbal manager. This flag is only for setting, is not reported. | + [Description("Enable gimbal manager. This flag is only for setting, is not reported.")] + ENABLE=16384, + /// Disable gimbal manager. This flag is only for setting, is not reported. | + [Description("Disable gimbal manager. This flag is only for setting, is not reported.")] + DISABLE=32768, + + }; + + /// Gimbal manager profiles. Only standard profiles are defined. Any implementation can define it's own profile in addition, and should use enum values > 16. + public enum MAV_STORM32_GIMBAL_MANAGER_PROFILE: byte + { + /// Default profile. Implementation specific. | + [Description("Default profile. Implementation specific.")] + DEFAULT=0, + /// Custom profile. Configurable profile according to the STorM32 definition. Is configured with STORM32_GIMBAL_MANAGER_PROFIL. | + [Description("Custom profile. Configurable profile according to the STorM32 definition. Is configured with STORM32_GIMBAL_MANAGER_PROFIL.")] + CUSTOM=1, + /// Default cooperative profile. Uses STorM32 custom profile with default settings to achieve cooperative behavior. | + [Description("Default cooperative profile. Uses STorM32 custom profile with default settings to achieve cooperative behavior.")] + COOPERATIVE=2, + /// Default exclusive profile. Uses STorM32 custom profile with default settings to achieve exclusive behavior. | + [Description("Default exclusive profile. Uses STorM32 custom profile with default settings to achieve exclusive behavior.")] + EXCLUSIVE=3, + /// Default priority profile with cooperative behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior. | + [Description("Default priority profile with cooperative behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior.")] + PRIORITY_COOPERATIVE=4, + /// Default priority profile with exclusive behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior. | + [Description("Default priority profile with exclusive behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior.")] + PRIORITY_EXCLUSIVE=5, + + }; + + /// Gimbal actions. + public enum MAV_STORM32_GIMBAL_ACTION: int /*default*/ + { + /// Trigger the gimbal device to recenter the gimbal. | + [Description("Trigger the gimbal device to recenter the gimbal.")] + RECENTER=1, + /// Trigger the gimbal device to run a calibration. | + [Description("Trigger the gimbal device to run a calibration.")] + CALIBRATION=2, + /// Trigger gimbal device to (re)discover the gimbal manager during run time. | + [Description("Trigger gimbal device to (re)discover the gimbal manager during run time.")] + DISCOVER_MANAGER=3, + + }; + + /// Enumeration of possible shot modes. + public enum MAV_QSHOT_MODE: ushort + { + /// Undefined shot mode. Can be used to determine if qshots should be used or not. | + [Description("Undefined shot mode. Can be used to determine if qshots should be used or not.")] + UNDEFINED=0, + /// Start normal gimbal operation. Is usally used to return back from a shot. | + [Description("Start normal gimbal operation. Is usally used to return back from a shot.")] + DEFAULT=1, + /// Load and keep safe gimbal position and stop stabilization. | + [Description("Load and keep safe gimbal position and stop stabilization.")] + GIMBAL_RETRACT=2, + /// Load neutral gimbal position and keep it while stabilizing. | + [Description("Load neutral gimbal position and keep it while stabilizing.")] + GIMBAL_NEUTRAL=3, + /// Start mission with gimbal control. | + [Description("Start mission with gimbal control.")] + GIMBAL_MISSION=4, + /// Start RC gimbal control. | + [Description("Start RC gimbal control.")] + GIMBAL_RC_CONTROL=5, + /// Start gimbal tracking the point specified by Lat, Lon, Alt. | + [Description("Start gimbal tracking the point specified by Lat, Lon, Alt.")] + POI_TARGETING=6, + /// Start gimbal tracking the system with specified system ID. | + [Description("Start gimbal tracking the system with specified system ID.")] + SYSID_TARGETING=7, + /// Start 2-point cable cam quick shot. | + [Description("Start 2-point cable cam quick shot.")] + CABLECAM_2POINT=8, + /// Start gimbal tracking the home location. | + [Description("Start gimbal tracking the home location.")] + HOME_TARGETING=9, + + }; + + + /// + public enum MAV_AVSS_COMMAND_FAILURE_REASON: int /*default*/ + { + /// AVSS defined command failure reason. PRS not steady. | + [Description("AVSS defined command failure reason. PRS not steady.")] + PRS_NOT_STEADY=1, + /// AVSS defined command failure reason. PRS DTM not armed. | + [Description("AVSS defined command failure reason. PRS DTM not armed.")] + PRS_DTM_NOT_ARMED=2, + /// AVSS defined command failure reason. PRS OTM not armed. | + [Description("AVSS defined command failure reason. PRS OTM not armed.")] + PRS_OTM_NOT_ARMED=3, + + }; + + /// + public enum AVSS_M300_OPERATION_MODE: int /*default*/ + { + /// In manual control mode | + [Description("In manual control mode")] + MODE_M300_MANUAL_CTRL=0, + /// In attitude mode | + [Description("In attitude mode ")] + MODE_M300_ATTITUDE=1, + /// In GPS mode | + [Description("In GPS mode")] + MODE_M300_P_GPS=6, + /// In hotpoint mode | + [Description("In hotpoint mode ")] + MODE_M300_HOTPOINT_MODE=9, + /// In assisted takeoff mode | + [Description("In assisted takeoff mode")] + MODE_M300_ASSISTED_TAKEOFF=10, + /// In auto takeoff mode | + [Description("In auto takeoff mode")] + MODE_M300_AUTO_TAKEOFF=11, + /// In auto landing mode | + [Description("In auto landing mode")] + MODE_M300_AUTO_LANDING=12, + /// In go home mode | + [Description("In go home mode")] + MODE_M300_NAVI_GO_HOME=15, + /// In sdk control mode | + [Description("In sdk control mode")] + MODE_M300_NAVI_SDK_CTRL=17, + /// In sport mode | + [Description("In sport mode")] + MODE_M300_S_SPORT=31, + /// In force auto landing mode | + [Description("In force auto landing mode")] + MODE_M300_FORCE_AUTO_LANDING=33, + /// In tripod mode | + [Description("In tripod mode")] + MODE_M300_T_TRIPOD=38, + /// In search mode | + [Description("In search mode")] + MODE_M300_SEARCH_MODE=40, + /// In engine mode | + [Description("In engine mode")] + MODE_M300_ENGINE_START=41, + + }; + + /// + public enum AVSS_HORSEFLY_OPERATION_MODE: int /*default*/ + { + /// In manual control mode | + [Description("In manual control mode")] + MODE_HORSEFLY_MANUAL_CTRL=0, + /// In auto takeoff mode | + [Description("In auto takeoff mode")] + MODE_HORSEFLY_AUTO_TAKEOFF=1, + /// In auto landing mode | + [Description("In auto landing mode")] + MODE_HORSEFLY_AUTO_LANDING=2, + /// In go home mode | + [Description("In go home mode")] + MODE_HORSEFLY_NAVI_GO_HOME=3, + /// In drop mode | + [Description("In drop mode")] + MODE_HORSEFLY_DROP=4, + + }; + + + + /// + 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, + + }; + + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=246)] + /// Information about video stream + public struct mavlink_zvideo_stream_information_t + { + /// packet ordered constructor + public mavlink_zvideo_stream_information_t(float framerate,uint bitrate,ushort resolution_h,ushort resolution_v,ushort rotation,byte camera_id,byte status,byte[] uri) + { + this.framerate = framerate; + this.bitrate = bitrate; + this.resolution_h = resolution_h; + this.resolution_v = resolution_v; + this.rotation = rotation; + this.camera_id = camera_id; + this.status = status; + this.uri = uri; + + } + + /// packet xml order + public static mavlink_zvideo_stream_information_t PopulateXMLOrder(byte camera_id,byte status,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,byte[] uri) + { + var msg = new mavlink_zvideo_stream_information_t(); + + msg.camera_id = camera_id; + msg.status = status; + msg.framerate = framerate; + msg.resolution_h = resolution_h; + msg.resolution_v = resolution_v; + msg.bitrate = bitrate; + msg.rotation = rotation; + msg.uri = uri; + + return msg; + } + + + /// Frame rate. [Hz] + [Units("[Hz]")] + [Description("Frame rate.")] + //[FieldOffset(0)] + public float framerate; + + /// Bit rate. [bits/s] + [Units("[bits/s]")] + [Description("Bit rate.")] + //[FieldOffset(4)] + public uint bitrate; + + /// Horizontal resolution. [pix] + [Units("[pix]")] + [Description("Horizontal resolution.")] + //[FieldOffset(8)] + public ushort resolution_h; + + /// Vertical resolution. [pix] + [Units("[pix]")] + [Description("Vertical resolution.")] + //[FieldOffset(10)] + public ushort resolution_v; + + /// Video image rotation clockwise. [deg] + [Units("[deg]")] + [Description("Video image rotation clockwise.")] + //[FieldOffset(12)] + public ushort rotation; + + /// Video Stream ID (1 for first, 2 for second, etc.) + [Units("")] + [Description("Video Stream ID (1 for first, 2 for second, etc.)")] + //[FieldOffset(14)] + public byte camera_id; + + /// Number of streams available. + [Units("")] + [Description("Number of streams available.")] + //[FieldOffset(15)] + public byte status; + + /// Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). + [Units("")] + [Description("Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=230)] + public byte[] uri; + }; + + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. + public struct mavlink_sensor_offsets_t + { + /// packet ordered constructor + public mavlink_sensor_offsets_t(float mag_declination,int raw_press,int raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z,short mag_ofs_x,short mag_ofs_y,short mag_ofs_z) + { + this.mag_declination = mag_declination; + this.raw_press = raw_press; + this.raw_temp = raw_temp; + this.gyro_cal_x = gyro_cal_x; + this.gyro_cal_y = gyro_cal_y; + this.gyro_cal_z = gyro_cal_z; + this.accel_cal_x = accel_cal_x; + this.accel_cal_y = accel_cal_y; + this.accel_cal_z = accel_cal_z; + this.mag_ofs_x = mag_ofs_x; + this.mag_ofs_y = mag_ofs_y; + this.mag_ofs_z = mag_ofs_z; + + } + + /// packet xml order + public static mavlink_sensor_offsets_t PopulateXMLOrder(short mag_ofs_x,short mag_ofs_y,short mag_ofs_z,float mag_declination,int raw_press,int raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z) + { + var msg = new mavlink_sensor_offsets_t(); + + msg.mag_ofs_x = mag_ofs_x; + msg.mag_ofs_y = mag_ofs_y; + msg.mag_ofs_z = mag_ofs_z; + msg.mag_declination = mag_declination; + msg.raw_press = raw_press; + msg.raw_temp = raw_temp; + msg.gyro_cal_x = gyro_cal_x; + msg.gyro_cal_y = gyro_cal_y; + msg.gyro_cal_z = gyro_cal_z; + msg.accel_cal_x = accel_cal_x; + msg.accel_cal_y = accel_cal_y; + msg.accel_cal_z = accel_cal_z; + + return msg; + } + + + /// Magnetic declination. [rad] + [Units("[rad]")] + [Description("Magnetic declination.")] + //[FieldOffset(0)] + public float mag_declination; + + /// Raw pressure from barometer. + [Units("")] + [Description("Raw pressure from barometer.")] + //[FieldOffset(4)] + public int raw_press; + + /// Raw temperature from barometer. + [Units("")] + [Description("Raw temperature from barometer.")] + //[FieldOffset(8)] + public int raw_temp; + + /// Gyro X calibration. + [Units("")] + [Description("Gyro X calibration.")] + //[FieldOffset(12)] + public float gyro_cal_x; + + /// Gyro Y calibration. + [Units("")] + [Description("Gyro Y calibration.")] + //[FieldOffset(16)] + public float gyro_cal_y; + + /// Gyro Z calibration. + [Units("")] + [Description("Gyro Z calibration.")] + //[FieldOffset(20)] + public float gyro_cal_z; + + /// Accel X calibration. + [Units("")] + [Description("Accel X calibration.")] + //[FieldOffset(24)] + public float accel_cal_x; + + /// Accel Y calibration. + [Units("")] + [Description("Accel Y calibration.")] + //[FieldOffset(28)] + public float accel_cal_y; + + /// Accel Z calibration. + [Units("")] + [Description("Accel Z calibration.")] + //[FieldOffset(32)] + public float accel_cal_z; + + /// Magnetometer X offset. + [Units("")] + [Description("Magnetometer X offset.")] + //[FieldOffset(36)] + public short mag_ofs_x; + + /// Magnetometer Y offset. + [Units("")] + [Description("Magnetometer Y offset.")] + //[FieldOffset(38)] + public short mag_ofs_y; + + /// Magnetometer Z offset. + [Units("")] + [Description("Magnetometer Z offset.")] + //[FieldOffset(40)] + public short mag_ofs_z; + }; + + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Set the magnetometer offsets + public struct mavlink_set_mag_offsets_t + { + /// packet ordered constructor + public mavlink_set_mag_offsets_t(short mag_ofs_x,short mag_ofs_y,short mag_ofs_z,byte target_system,byte target_component) + { + this.mag_ofs_x = mag_ofs_x; + this.mag_ofs_y = mag_ofs_y; + this.mag_ofs_z = mag_ofs_z; + this.target_system = target_system; + this.target_component = target_component; + + } + + /// packet xml order + public static mavlink_set_mag_offsets_t PopulateXMLOrder(byte target_system,byte target_component,short mag_ofs_x,short mag_ofs_y,short mag_ofs_z) + { + var msg = new mavlink_set_mag_offsets_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.mag_ofs_x = mag_ofs_x; + msg.mag_ofs_y = mag_ofs_y; + msg.mag_ofs_z = mag_ofs_z; + + return msg; + } + + + /// Magnetometer X offset. + [Units("")] + [Description("Magnetometer X offset.")] + //[FieldOffset(0)] + public short mag_ofs_x; + + /// Magnetometer Y offset. + [Units("")] + [Description("Magnetometer Y offset.")] + //[FieldOffset(2)] + public short mag_ofs_y; + + /// Magnetometer Z offset. + [Units("")] + [Description("Magnetometer Z offset.")] + //[FieldOffset(4)] + public short mag_ofs_z; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(6)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(7)] + public byte target_component; + }; + + + /// extensions_start 2 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// State of autopilot RAM. + public struct mavlink_meminfo_t + { + /// packet ordered constructor + public mavlink_meminfo_t(ushort brkval,ushort freemem,uint freemem32) + { + this.brkval = brkval; + this.freemem = freemem; + this.freemem32 = freemem32; + + } + + /// packet xml order + public static mavlink_meminfo_t PopulateXMLOrder(ushort brkval,ushort freemem,uint freemem32) + { + var msg = new mavlink_meminfo_t(); + + msg.brkval = brkval; + msg.freemem = freemem; + msg.freemem32 = freemem32; + + return msg; + } + + + /// Heap top. + [Units("")] + [Description("Heap top.")] + //[FieldOffset(0)] + public ushort brkval; + + /// Free memory. [bytes] + [Units("[bytes]")] + [Description("Free memory.")] + //[FieldOffset(2)] + public ushort freemem; + + /// Free memory (32 bit). [bytes] + [Units("[bytes]")] + [Description("Free memory (32 bit).")] + //[FieldOffset(4)] + public uint freemem32; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// Raw ADC output. + public struct mavlink_ap_adc_t + { + /// packet ordered constructor + public mavlink_ap_adc_t(ushort adc1,ushort adc2,ushort adc3,ushort adc4,ushort adc5,ushort adc6) + { + this.adc1 = adc1; + this.adc2 = adc2; + this.adc3 = adc3; + this.adc4 = adc4; + this.adc5 = adc5; + this.adc6 = adc6; + + } + + /// packet xml order + public static mavlink_ap_adc_t PopulateXMLOrder(ushort adc1,ushort adc2,ushort adc3,ushort adc4,ushort adc5,ushort adc6) + { + var msg = new mavlink_ap_adc_t(); + + msg.adc1 = adc1; + msg.adc2 = adc2; + msg.adc3 = adc3; + msg.adc4 = adc4; + msg.adc5 = adc5; + msg.adc6 = adc6; + + return msg; + } + + + /// ADC output 1. + [Units("")] + [Description("ADC output 1.")] + //[FieldOffset(0)] + public ushort adc1; + + /// ADC output 2. + [Units("")] + [Description("ADC output 2.")] + //[FieldOffset(2)] + public ushort adc2; + + /// ADC output 3. + [Units("")] + [Description("ADC output 3.")] + //[FieldOffset(4)] + public ushort adc3; + + /// ADC output 4. + [Units("")] + [Description("ADC output 4.")] + //[FieldOffset(6)] + public ushort adc4; + + /// ADC output 5. + [Units("")] + [Description("ADC output 5.")] + //[FieldOffset(8)] + public ushort adc5; + + /// ADC output 6. + [Units("")] + [Description("ADC output 6.")] + //[FieldOffset(10)] + public ushort adc6; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] + /// Configure on-board Camera Control System. + public struct mavlink_digicam_configure_t + { + /// packet ordered constructor + public mavlink_digicam_configure_t(float extra_value,ushort shutter_speed,byte target_system,byte target_component,byte mode,byte aperture,byte iso,byte exposure_type,byte command_id,byte engine_cut_off,byte extra_param) + { + this.extra_value = extra_value; + this.shutter_speed = shutter_speed; + this.target_system = target_system; + this.target_component = target_component; + this.mode = mode; + this.aperture = aperture; + this.iso = iso; + this.exposure_type = exposure_type; + this.command_id = command_id; + this.engine_cut_off = engine_cut_off; + this.extra_param = extra_param; + + } + + /// packet xml order + public static mavlink_digicam_configure_t PopulateXMLOrder(byte target_system,byte target_component,byte mode,ushort shutter_speed,byte aperture,byte iso,byte exposure_type,byte command_id,byte engine_cut_off,byte extra_param,float extra_value) + { + var msg = new mavlink_digicam_configure_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.mode = mode; + msg.shutter_speed = shutter_speed; + msg.aperture = aperture; + msg.iso = iso; + msg.exposure_type = exposure_type; + msg.command_id = command_id; + msg.engine_cut_off = engine_cut_off; + msg.extra_param = extra_param; + msg.extra_value = extra_value; + + return msg; + } + + + /// Correspondent value to given extra_param. + [Units("")] + [Description("Correspondent value to given extra_param.")] + //[FieldOffset(0)] + public float extra_value; + + /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore). + [Units("")] + [Description("Divisor number //e.g. 1000 means 1/1000 (0 means ignore).")] + //[FieldOffset(4)] + public ushort shutter_speed; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(6)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(7)] + public byte target_component; + + /// Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore). + [Units("")] + [Description("Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).")] + //[FieldOffset(8)] + public byte mode; + + /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore). + [Units("")] + [Description("F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).")] + //[FieldOffset(9)] + public byte aperture; + + /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore). + [Units("")] + [Description("ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).")] + //[FieldOffset(10)] + public byte iso; + + /// Exposure type enumeration from 1 to N (0 means ignore). + [Units("")] + [Description("Exposure type enumeration from 1 to N (0 means ignore).")] + //[FieldOffset(11)] + public byte exposure_type; + + /// Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once. + [Units("")] + [Description("Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.")] + //[FieldOffset(12)] + public byte command_id; + + /// Main engine cut-off time before camera trigger (0 means no cut-off). [ds] + [Units("[ds]")] + [Description("Main engine cut-off time before camera trigger (0 means no cut-off).")] + //[FieldOffset(13)] + public byte engine_cut_off; + + /// Extra parameters enumeration (0 means ignore). + [Units("")] + [Description("Extra parameters enumeration (0 means ignore).")] + //[FieldOffset(14)] + public byte extra_param; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] + /// Control on-board Camera Control System to take shots. + public struct mavlink_digicam_control_t + { + /// packet ordered constructor + public mavlink_digicam_control_t(float extra_value,byte target_system,byte target_component,byte session,byte zoom_pos,sbyte zoom_step,byte focus_lock,byte shot,byte command_id,byte extra_param) + { + this.extra_value = extra_value; + this.target_system = target_system; + this.target_component = target_component; + this.session = session; + this.zoom_pos = zoom_pos; + this.zoom_step = zoom_step; + this.focus_lock = focus_lock; + this.shot = shot; + this.command_id = command_id; + this.extra_param = extra_param; + + } + + /// packet xml order + public static mavlink_digicam_control_t PopulateXMLOrder(byte target_system,byte target_component,byte session,byte zoom_pos,sbyte zoom_step,byte focus_lock,byte shot,byte command_id,byte extra_param,float extra_value) + { + var msg = new mavlink_digicam_control_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.session = session; + msg.zoom_pos = zoom_pos; + msg.zoom_step = zoom_step; + msg.focus_lock = focus_lock; + msg.shot = shot; + msg.command_id = command_id; msg.extra_param = extra_param; msg.extra_value = extra_value; @@ -7512,6656 +8507,11340 @@ public static mavlink_digicam_control_t PopulateXMLOrder(byte target_system,byte } - /// Correspondent value to given extra_param. + /// Correspondent value to given extra_param. + [Units("")] + [Description("Correspondent value to given extra_param.")] + //[FieldOffset(0)] + public float extra_value; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(4)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; + + /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens. + [Units("")] + [Description("0: stop, 1: start or keep it up //Session control e.g. show/hide lens.")] + //[FieldOffset(6)] + public byte session; + + /// 1 to N //Zoom's absolute position (0 means ignore). + [Units("")] + [Description("1 to N //Zoom's absolute position (0 means ignore).")] + //[FieldOffset(7)] + public byte zoom_pos; + + /// -100 to 100 //Zooming step value to offset zoom from the current position. + [Units("")] + [Description("-100 to 100 //Zooming step value to offset zoom from the current position.")] + //[FieldOffset(8)] + public sbyte zoom_step; + + /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus. + [Units("")] + [Description("0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.")] + //[FieldOffset(9)] + public byte focus_lock; + + /// 0: ignore, 1: shot or start filming. + [Units("")] + [Description("0: ignore, 1: shot or start filming.")] + //[FieldOffset(10)] + public byte shot; + + /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once. + [Units("")] + [Description("Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.")] + //[FieldOffset(11)] + public byte command_id; + + /// Extra parameters enumeration (0 means ignore). + [Units("")] + [Description("Extra parameters enumeration (0 means ignore).")] + //[FieldOffset(12)] + public byte extra_param; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Message to configure a camera mount, directional antenna, etc. + public struct mavlink_mount_configure_t + { + /// packet ordered constructor + public mavlink_mount_configure_t(byte target_system,byte target_component,/*MAV_MOUNT_MODE*/byte mount_mode,byte stab_roll,byte stab_pitch,byte stab_yaw) + { + this.target_system = target_system; + this.target_component = target_component; + this.mount_mode = mount_mode; + this.stab_roll = stab_roll; + this.stab_pitch = stab_pitch; + this.stab_yaw = stab_yaw; + + } + + /// packet xml order + public static mavlink_mount_configure_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MOUNT_MODE*/byte mount_mode,byte stab_roll,byte stab_pitch,byte stab_yaw) + { + var msg = new mavlink_mount_configure_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.mount_mode = mount_mode; + msg.stab_roll = stab_roll; + msg.stab_pitch = stab_pitch; + msg.stab_yaw = stab_yaw; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + + /// Mount operating mode. MAV_MOUNT_MODE + [Units("")] + [Description("Mount operating mode.")] + //[FieldOffset(2)] + public /*MAV_MOUNT_MODE*/byte mount_mode; + + /// (1 = yes, 0 = no). + [Units("")] + [Description("(1 = yes, 0 = no).")] + //[FieldOffset(3)] + public byte stab_roll; + + /// (1 = yes, 0 = no). + [Units("")] + [Description("(1 = yes, 0 = no).")] + //[FieldOffset(4)] + public byte stab_pitch; + + /// (1 = yes, 0 = no). + [Units("")] + [Description("(1 = yes, 0 = no).")] + //[FieldOffset(5)] + public byte stab_yaw; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] + /// Message to control a camera mount, directional antenna, etc. + public struct mavlink_mount_control_t + { + /// packet ordered constructor + public mavlink_mount_control_t(int input_a,int input_b,int input_c,byte target_system,byte target_component,byte save_position) + { + this.input_a = input_a; + this.input_b = input_b; + this.input_c = input_c; + this.target_system = target_system; + this.target_component = target_component; + this.save_position = save_position; + + } + + /// packet xml order + public static mavlink_mount_control_t PopulateXMLOrder(byte target_system,byte target_component,int input_a,int input_b,int input_c,byte save_position) + { + var msg = new mavlink_mount_control_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.input_a = input_a; + msg.input_b = input_b; + msg.input_c = input_c; + msg.save_position = save_position; + + return msg; + } + + + /// Pitch (centi-degrees) or lat (degE7), depending on mount mode. + [Units("")] + [Description("Pitch (centi-degrees) or lat (degE7), depending on mount mode.")] + //[FieldOffset(0)] + public int input_a; + + /// Roll (centi-degrees) or lon (degE7) depending on mount mode. + [Units("")] + [Description("Roll (centi-degrees) or lon (degE7) depending on mount mode.")] + //[FieldOffset(4)] + public int input_b; + + /// Yaw (centi-degrees) or alt (cm) depending on mount mode. + [Units("")] + [Description("Yaw (centi-degrees) or alt (cm) depending on mount mode.")] + //[FieldOffset(8)] + public int input_c; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(12)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(13)] + public byte target_component; + + /// If '1' it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING). + [Units("")] + [Description("If '1' it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).")] + //[FieldOffset(14)] + public byte save_position; + }; + + + /// extensions_start 5 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] + /// Message with some status from autopilot to GCS about camera or antenna mount. + public struct mavlink_mount_status_t + { + /// packet ordered constructor + public mavlink_mount_status_t(int pointing_a,int pointing_b,int pointing_c,byte target_system,byte target_component,/*MAV_MOUNT_MODE*/byte mount_mode) + { + this.pointing_a = pointing_a; + this.pointing_b = pointing_b; + this.pointing_c = pointing_c; + this.target_system = target_system; + this.target_component = target_component; + this.mount_mode = mount_mode; + + } + + /// packet xml order + public static mavlink_mount_status_t PopulateXMLOrder(byte target_system,byte target_component,int pointing_a,int pointing_b,int pointing_c,/*MAV_MOUNT_MODE*/byte mount_mode) + { + var msg = new mavlink_mount_status_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.pointing_a = pointing_a; + msg.pointing_b = pointing_b; + msg.pointing_c = pointing_c; + msg.mount_mode = mount_mode; + + return msg; + } + + + /// Pitch. [cdeg] + [Units("[cdeg]")] + [Description("Pitch.")] + //[FieldOffset(0)] + public int pointing_a; + + /// Roll. [cdeg] + [Units("[cdeg]")] + [Description("Roll.")] + //[FieldOffset(4)] + public int pointing_b; + + /// Yaw. [cdeg] + [Units("[cdeg]")] + [Description("Yaw.")] + //[FieldOffset(8)] + public int pointing_c; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(12)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(13)] + public byte target_component; + + /// Mount operating mode. MAV_MOUNT_MODE + [Units("")] + [Description("Mount operating mode.")] + //[FieldOffset(14)] + public /*MAV_MOUNT_MODE*/byte mount_mode; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS. + public struct mavlink_fence_point_t + { + /// packet ordered constructor + public mavlink_fence_point_t(float lat,float lng,byte target_system,byte target_component,byte idx,byte count) + { + this.lat = lat; + this.lng = lng; + this.target_system = target_system; + this.target_component = target_component; + this.idx = idx; + this.count = count; + + } + + /// packet xml order + public static mavlink_fence_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx,byte count,float lat,float lng) + { + var msg = new mavlink_fence_point_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.idx = idx; + msg.count = count; + msg.lat = lat; + msg.lng = lng; + + return msg; + } + + + /// Latitude of point. [deg] + [Units("[deg]")] + [Description("Latitude of point.")] + //[FieldOffset(0)] + public float lat; + + /// Longitude of point. [deg] + [Units("[deg]")] + [Description("Longitude of point.")] + //[FieldOffset(4)] + public float lng; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(8)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(9)] + public byte target_component; + + /// Point index (first point is 1, 0 is for return point). + [Units("")] + [Description("Point index (first point is 1, 0 is for return point).")] + //[FieldOffset(10)] + public byte idx; + + /// Total number of points (for sanity checking). + [Units("")] + [Description("Total number of points (for sanity checking).")] + //[FieldOffset(11)] + public byte count; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Request a current fence point from MAV. + public struct mavlink_fence_fetch_point_t + { + /// packet ordered constructor + public mavlink_fence_fetch_point_t(byte target_system,byte target_component,byte idx) + { + this.target_system = target_system; + this.target_component = target_component; + this.idx = idx; + + } + + /// packet xml order + public static mavlink_fence_fetch_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx) + { + var msg = new mavlink_fence_fetch_point_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.idx = idx; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + + /// Point index (first point is 1, 0 is for return point). + [Units("")] + [Description("Point index (first point is 1, 0 is for return point).")] + //[FieldOffset(2)] + public byte idx; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// Status of DCM attitude estimator. + public struct mavlink_ahrs_t + { + /// packet ordered constructor + public mavlink_ahrs_t(float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) + { + this.omegaIx = omegaIx; + this.omegaIy = omegaIy; + this.omegaIz = omegaIz; + this.accel_weight = accel_weight; + this.renorm_val = renorm_val; + this.error_rp = error_rp; + this.error_yaw = error_yaw; + + } + + /// packet xml order + public static mavlink_ahrs_t PopulateXMLOrder(float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) + { + var msg = new mavlink_ahrs_t(); + + msg.omegaIx = omegaIx; + msg.omegaIy = omegaIy; + msg.omegaIz = omegaIz; + msg.accel_weight = accel_weight; + msg.renorm_val = renorm_val; + msg.error_rp = error_rp; + msg.error_yaw = error_yaw; + + return msg; + } + + + /// X gyro drift estimate. [rad/s] + [Units("[rad/s]")] + [Description("X gyro drift estimate.")] + //[FieldOffset(0)] + public float omegaIx; + + /// Y gyro drift estimate. [rad/s] + [Units("[rad/s]")] + [Description("Y gyro drift estimate.")] + //[FieldOffset(4)] + public float omegaIy; + + /// Z gyro drift estimate. [rad/s] + [Units("[rad/s]")] + [Description("Z gyro drift estimate.")] + //[FieldOffset(8)] + public float omegaIz; + + /// Average accel_weight. + [Units("")] + [Description("Average accel_weight.")] + //[FieldOffset(12)] + public float accel_weight; + + /// Average renormalisation value. + [Units("")] + [Description("Average renormalisation value.")] + //[FieldOffset(16)] + public float renorm_val; + + /// Average error_roll_pitch value. + [Units("")] + [Description("Average error_roll_pitch value.")] + //[FieldOffset(20)] + public float error_rp; + + /// Average error_yaw value. + [Units("")] + [Description("Average error_yaw value.")] + //[FieldOffset(24)] + public float error_yaw; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// Status of simulation environment, if used. + public struct mavlink_simstate_t + { + /// packet ordered constructor + public mavlink_simstate_t(float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int lat,int lng) + { + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.lat = lat; + this.lng = lng; + + } + + /// packet xml order + public static mavlink_simstate_t PopulateXMLOrder(float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int lat,int lng) + { + var msg = new mavlink_simstate_t(); + + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.lat = lat; + msg.lng = lng; + + return msg; + } + + + /// Roll angle. [rad] + [Units("[rad]")] + [Description("Roll angle.")] + //[FieldOffset(0)] + public float roll; + + /// Pitch angle. [rad] + [Units("[rad]")] + [Description("Pitch angle.")] + //[FieldOffset(4)] + public float pitch; + + /// Yaw angle. [rad] + [Units("[rad]")] + [Description("Yaw angle.")] + //[FieldOffset(8)] + public float yaw; + + /// X acceleration. [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration.")] + //[FieldOffset(12)] + public float xacc; + + /// Y acceleration. [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration.")] + //[FieldOffset(16)] + public float yacc; + + /// Z acceleration. [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration.")] + //[FieldOffset(20)] + public float zacc; + + /// Angular speed around X axis. [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around X axis.")] + //[FieldOffset(24)] + public float xgyro; + + /// Angular speed around Y axis. [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Y axis.")] + //[FieldOffset(28)] + public float ygyro; + + /// Angular speed around Z axis. [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Z axis.")] + //[FieldOffset(32)] + public float zgyro; + + /// Latitude. [degE7] + [Units("[degE7]")] + [Description("Latitude.")] + //[FieldOffset(36)] + public int lat; + + /// Longitude. [degE7] + [Units("[degE7]")] + [Description("Longitude.")] + //[FieldOffset(40)] + public int lng; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Status of key hardware. + public struct mavlink_hwstatus_t + { + /// packet ordered constructor + public mavlink_hwstatus_t(ushort Vcc,byte I2Cerr) + { + this.Vcc = Vcc; + this.I2Cerr = I2Cerr; + + } + + /// packet xml order + public static mavlink_hwstatus_t PopulateXMLOrder(ushort Vcc,byte I2Cerr) + { + var msg = new mavlink_hwstatus_t(); + + msg.Vcc = Vcc; + msg.I2Cerr = I2Cerr; + + return msg; + } + + + /// Board voltage. [mV] + [Units("[mV]")] + [Description("Board voltage.")] + //[FieldOffset(0)] + public ushort Vcc; + + /// I2C error count. + [Units("")] + [Description("I2C error count.")] + //[FieldOffset(2)] + public byte I2Cerr; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Status generated by radio. + public struct mavlink_radio_t + { + /// packet ordered constructor + public mavlink_radio_t(ushort rxerrors,ushort @fixed,byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise) + { + this.rxerrors = rxerrors; + this.@fixed = @fixed; + this.rssi = rssi; + this.remrssi = remrssi; + this.txbuf = txbuf; + this.noise = noise; + this.remnoise = remnoise; + + } + + /// packet xml order + public static mavlink_radio_t PopulateXMLOrder(byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise,ushort rxerrors,ushort @fixed) + { + var msg = new mavlink_radio_t(); + + msg.rssi = rssi; + msg.remrssi = remrssi; + msg.txbuf = txbuf; + msg.noise = noise; + msg.remnoise = remnoise; + msg.rxerrors = rxerrors; + msg.@fixed = @fixed; + + return msg; + } + + + /// Receive errors. + [Units("")] + [Description("Receive errors.")] + //[FieldOffset(0)] + public ushort rxerrors; + + /// Count of error corrected packets. + [Units("")] + [Description("Count of error corrected packets.")] + //[FieldOffset(2)] + public ushort @fixed; + + /// Local signal strength. + [Units("")] + [Description("Local signal strength.")] + //[FieldOffset(4)] + public byte rssi; + + /// Remote signal strength. + [Units("")] + [Description("Remote signal strength.")] + //[FieldOffset(5)] + public byte remrssi; + + /// How full the tx buffer is. [%] + [Units("[%]")] + [Description("How full the tx buffer is.")] + //[FieldOffset(6)] + public byte txbuf; + + /// Background noise level. + [Units("")] + [Description("Background noise level.")] + //[FieldOffset(7)] + public byte noise; + + /// Remote background noise level. + [Units("")] + [Description("Remote background noise level.")] + //[FieldOffset(8)] + public byte remnoise; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] + /// Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled. + public struct mavlink_limits_status_t + { + /// packet ordered constructor + public mavlink_limits_status_t(uint last_trigger,uint last_action,uint last_recovery,uint last_clear,ushort breach_count,/*LIMITS_STATE*/byte limits_state,/*LIMIT_MODULE*/byte mods_enabled,/*LIMIT_MODULE*/byte mods_required,/*LIMIT_MODULE*/byte mods_triggered) + { + this.last_trigger = last_trigger; + this.last_action = last_action; + this.last_recovery = last_recovery; + this.last_clear = last_clear; + this.breach_count = breach_count; + this.limits_state = limits_state; + this.mods_enabled = mods_enabled; + this.mods_required = mods_required; + this.mods_triggered = mods_triggered; + + } + + /// packet xml order + public static mavlink_limits_status_t PopulateXMLOrder(/*LIMITS_STATE*/byte limits_state,uint last_trigger,uint last_action,uint last_recovery,uint last_clear,ushort breach_count,/*LIMIT_MODULE*/byte mods_enabled,/*LIMIT_MODULE*/byte mods_required,/*LIMIT_MODULE*/byte mods_triggered) + { + var msg = new mavlink_limits_status_t(); + + msg.limits_state = limits_state; + msg.last_trigger = last_trigger; + msg.last_action = last_action; + msg.last_recovery = last_recovery; + msg.last_clear = last_clear; + msg.breach_count = breach_count; + msg.mods_enabled = mods_enabled; + msg.mods_required = mods_required; + msg.mods_triggered = mods_triggered; + + return msg; + } + + + /// Time (since boot) of last breach. [ms] + [Units("[ms]")] + [Description("Time (since boot) of last breach.")] + //[FieldOffset(0)] + public uint last_trigger; + + /// Time (since boot) of last recovery action. [ms] + [Units("[ms]")] + [Description("Time (since boot) of last recovery action.")] + //[FieldOffset(4)] + public uint last_action; + + /// Time (since boot) of last successful recovery. [ms] + [Units("[ms]")] + [Description("Time (since boot) of last successful recovery.")] + //[FieldOffset(8)] + public uint last_recovery; + + /// Time (since boot) of last all-clear. [ms] + [Units("[ms]")] + [Description("Time (since boot) of last all-clear.")] + //[FieldOffset(12)] + public uint last_clear; + + /// Number of fence breaches. + [Units("")] + [Description("Number of fence breaches.")] + //[FieldOffset(16)] + public ushort breach_count; + + /// State of AP_Limits. LIMITS_STATE + [Units("")] + [Description("State of AP_Limits.")] + //[FieldOffset(18)] + public /*LIMITS_STATE*/byte limits_state; + + /// AP_Limit_Module bitfield of enabled modules. LIMIT_MODULE bitmask + [Units("")] + [Description("AP_Limit_Module bitfield of enabled modules.")] + //[FieldOffset(19)] + public /*LIMIT_MODULE*/byte mods_enabled; + + /// AP_Limit_Module bitfield of required modules. LIMIT_MODULE bitmask + [Units("")] + [Description("AP_Limit_Module bitfield of required modules.")] + //[FieldOffset(20)] + public /*LIMIT_MODULE*/byte mods_required; + + /// AP_Limit_Module bitfield of triggered modules. LIMIT_MODULE bitmask + [Units("")] + [Description("AP_Limit_Module bitfield of triggered modules.")] + //[FieldOffset(21)] + public /*LIMIT_MODULE*/byte mods_triggered; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// Wind estimation. + public struct mavlink_wind_t + { + /// packet ordered constructor + public mavlink_wind_t(float direction,float speed,float speed_z) + { + this.direction = direction; + this.speed = speed; + this.speed_z = speed_z; + + } + + /// packet xml order + public static mavlink_wind_t PopulateXMLOrder(float direction,float speed,float speed_z) + { + var msg = new mavlink_wind_t(); + + msg.direction = direction; + msg.speed = speed; + msg.speed_z = speed_z; + + return msg; + } + + + /// Wind direction (that wind is coming from). [deg] + [Units("[deg]")] + [Description("Wind direction (that wind is coming from).")] + //[FieldOffset(0)] + public float direction; + + /// Wind speed in ground plane. [m/s] + [Units("[m/s]")] + [Description("Wind speed in ground plane.")] + //[FieldOffset(4)] + public float speed; + + /// Vertical wind speed. [m/s] + [Units("[m/s]")] + [Description("Vertical wind speed.")] + //[FieldOffset(8)] + public float speed_z; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] + /// Data packet, size 16. + public struct mavlink_data16_t + { + /// packet ordered constructor + public mavlink_data16_t(byte type,byte len,byte[] data) + { + this.type = type; + this.len = len; + this.data = data; + + } + + /// packet xml order + public static mavlink_data16_t PopulateXMLOrder(byte type,byte len,byte[] data) + { + var msg = new mavlink_data16_t(); + + msg.type = type; + msg.len = len; + msg.data = data; + + return msg; + } + + + /// Data type. + [Units("")] + [Description("Data type.")] + //[FieldOffset(0)] + public byte type; + + /// Data length. [bytes] + [Units("[bytes]")] + [Description("Data length.")] + //[FieldOffset(1)] + public byte len; + + /// Raw data. + [Units("")] + [Description("Raw data.")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] data; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] + /// Data packet, size 32. + public struct mavlink_data32_t + { + /// packet ordered constructor + public mavlink_data32_t(byte type,byte len,byte[] data) + { + this.type = type; + this.len = len; + this.data = data; + + } + + /// packet xml order + public static mavlink_data32_t PopulateXMLOrder(byte type,byte len,byte[] data) + { + var msg = new mavlink_data32_t(); + + msg.type = type; + msg.len = len; + msg.data = data; + + return msg; + } + + + /// Data type. + [Units("")] + [Description("Data type.")] + //[FieldOffset(0)] + public byte type; + + /// Data length. [bytes] + [Units("[bytes]")] + [Description("Data length.")] + //[FieldOffset(1)] + public byte len; + + /// Raw data. + [Units("")] + [Description("Raw data.")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] data; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=66)] + /// Data packet, size 64. + public struct mavlink_data64_t + { + /// packet ordered constructor + public mavlink_data64_t(byte type,byte len,byte[] data) + { + this.type = type; + this.len = len; + this.data = data; + + } + + /// packet xml order + public static mavlink_data64_t PopulateXMLOrder(byte type,byte len,byte[] data) + { + var msg = new mavlink_data64_t(); + + msg.type = type; + msg.len = len; + msg.data = data; + + return msg; + } + + + /// Data type. + [Units("")] + [Description("Data type.")] + //[FieldOffset(0)] + public byte type; + + /// Data length. [bytes] + [Units("[bytes]")] + [Description("Data length.")] + //[FieldOffset(1)] + public byte len; + + /// Raw data. + [Units("")] + [Description("Raw data.")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=64)] + public byte[] data; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=98)] + /// Data packet, size 96. + public struct mavlink_data96_t + { + /// packet ordered constructor + public mavlink_data96_t(byte type,byte len,byte[] data) + { + this.type = type; + this.len = len; + this.data = data; + + } + + /// packet xml order + public static mavlink_data96_t PopulateXMLOrder(byte type,byte len,byte[] data) + { + var msg = new mavlink_data96_t(); + + msg.type = type; + msg.len = len; + msg.data = data; + + return msg; + } + + + /// Data type. + [Units("")] + [Description("Data type.")] + //[FieldOffset(0)] + public byte type; + + /// Data length. [bytes] + [Units("[bytes]")] + [Description("Data length.")] + //[FieldOffset(1)] + public byte len; + + /// Raw data. + [Units("")] + [Description("Raw data.")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=96)] + public byte[] data; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Rangefinder reporting. + public struct mavlink_rangefinder_t + { + /// packet ordered constructor + public mavlink_rangefinder_t(float distance,float voltage) + { + this.distance = distance; + this.voltage = voltage; + + } + + /// packet xml order + public static mavlink_rangefinder_t PopulateXMLOrder(float distance,float voltage) + { + var msg = new mavlink_rangefinder_t(); + + msg.distance = distance; + msg.voltage = voltage; + + return msg; + } + + + /// Distance. [m] + [Units("[m]")] + [Description("Distance.")] + //[FieldOffset(0)] + public float distance; + + /// Raw voltage if available, zero otherwise. [V] + [Units("[V]")] + [Description("Raw voltage if available, zero otherwise.")] + //[FieldOffset(4)] + public float voltage; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=48)] + /// Airspeed auto-calibration. + public struct mavlink_airspeed_autocal_t + { + /// packet ordered constructor + public mavlink_airspeed_autocal_t(float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz) + { + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.diff_pressure = diff_pressure; + this.EAS2TAS = EAS2TAS; + this.ratio = ratio; + this.state_x = state_x; + this.state_y = state_y; + this.state_z = state_z; + this.Pax = Pax; + this.Pby = Pby; + this.Pcz = Pcz; + + } + + /// packet xml order + public static mavlink_airspeed_autocal_t PopulateXMLOrder(float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz) + { + var msg = new mavlink_airspeed_autocal_t(); + + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.diff_pressure = diff_pressure; + msg.EAS2TAS = EAS2TAS; + msg.ratio = ratio; + msg.state_x = state_x; + msg.state_y = state_y; + msg.state_z = state_z; + msg.Pax = Pax; + msg.Pby = Pby; + msg.Pcz = Pcz; + + return msg; + } + + + /// GPS velocity north. [m/s] + [Units("[m/s]")] + [Description("GPS velocity north.")] + //[FieldOffset(0)] + public float vx; + + /// GPS velocity east. [m/s] + [Units("[m/s]")] + [Description("GPS velocity east.")] + //[FieldOffset(4)] + public float vy; + + /// GPS velocity down. [m/s] + [Units("[m/s]")] + [Description("GPS velocity down.")] + //[FieldOffset(8)] + public float vz; + + /// Differential pressure. [Pa] + [Units("[Pa]")] + [Description("Differential pressure.")] + //[FieldOffset(12)] + public float diff_pressure; + + /// Estimated to true airspeed ratio. + [Units("")] + [Description("Estimated to true airspeed ratio.")] + //[FieldOffset(16)] + public float EAS2TAS; + + /// Airspeed ratio. + [Units("")] + [Description("Airspeed ratio.")] + //[FieldOffset(20)] + public float ratio; + + /// EKF state x. + [Units("")] + [Description("EKF state x.")] + //[FieldOffset(24)] + public float state_x; + + /// EKF state y. + [Units("")] + [Description("EKF state y.")] + //[FieldOffset(28)] + public float state_y; + + /// EKF state z. + [Units("")] + [Description("EKF state z.")] + //[FieldOffset(32)] + public float state_z; + + /// EKF Pax. + [Units("")] + [Description("EKF Pax.")] + //[FieldOffset(36)] + public float Pax; + + /// EKF Pby. + [Units("")] + [Description("EKF Pby.")] + //[FieldOffset(40)] + public float Pby; + + /// EKF Pcz. + [Units("")] + [Description("EKF Pcz.")] + //[FieldOffset(44)] + public float Pcz; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] + /// A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS. + public struct mavlink_rally_point_t + { + /// packet ordered constructor + public mavlink_rally_point_t(int lat,int lng,short alt,short break_alt,ushort land_dir,byte target_system,byte target_component,byte idx,byte count,/*RALLY_FLAGS*/byte flags) + { + this.lat = lat; + this.lng = lng; + this.alt = alt; + this.break_alt = break_alt; + this.land_dir = land_dir; + this.target_system = target_system; + this.target_component = target_component; + this.idx = idx; + this.count = count; + this.flags = flags; + + } + + /// packet xml order + public static mavlink_rally_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx,byte count,int lat,int lng,short alt,short break_alt,ushort land_dir,/*RALLY_FLAGS*/byte flags) + { + var msg = new mavlink_rally_point_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.idx = idx; + msg.count = count; + msg.lat = lat; + msg.lng = lng; + msg.alt = alt; + msg.break_alt = break_alt; + msg.land_dir = land_dir; + msg.flags = flags; + + return msg; + } + + + /// Latitude of point. [degE7] + [Units("[degE7]")] + [Description("Latitude of point.")] + //[FieldOffset(0)] + public int lat; + + /// Longitude of point. [degE7] + [Units("[degE7]")] + [Description("Longitude of point.")] + //[FieldOffset(4)] + public int lng; + + /// Transit / loiter altitude relative to home. [m] + [Units("[m]")] + [Description("Transit / loiter altitude relative to home.")] + //[FieldOffset(8)] + public short alt; + + /// Break altitude relative to home. [m] + [Units("[m]")] + [Description("Break altitude relative to home.")] + //[FieldOffset(10)] + public short break_alt; + + /// Heading to aim for when landing. [cdeg] + [Units("[cdeg]")] + [Description("Heading to aim for when landing.")] + //[FieldOffset(12)] + public ushort land_dir; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(14)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(15)] + public byte target_component; + + /// Point index (first point is 0). + [Units("")] + [Description("Point index (first point is 0).")] + //[FieldOffset(16)] + public byte idx; + + /// Total number of points (for sanity checking). + [Units("")] + [Description("Total number of points (for sanity checking).")] + //[FieldOffset(17)] + public byte count; + + /// Configuration flags. RALLY_FLAGS bitmask + [Units("")] + [Description("Configuration flags.")] + //[FieldOffset(18)] + public /*RALLY_FLAGS*/byte flags; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. + public struct mavlink_rally_fetch_point_t + { + /// packet ordered constructor + public mavlink_rally_fetch_point_t(byte target_system,byte target_component,byte idx) + { + this.target_system = target_system; + this.target_component = target_component; + this.idx = idx; + + } + + /// packet xml order + public static mavlink_rally_fetch_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx) + { + var msg = new mavlink_rally_fetch_point_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.idx = idx; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + + /// Point index (first point is 0). + [Units("")] + [Description("Point index (first point is 0).")] + //[FieldOffset(2)] + public byte idx; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Status of compassmot calibration. + public struct mavlink_compassmot_status_t + { + /// packet ordered constructor + public mavlink_compassmot_status_t(float current,float CompensationX,float CompensationY,float CompensationZ,ushort throttle,ushort interference) + { + this.current = current; + this.CompensationX = CompensationX; + this.CompensationY = CompensationY; + this.CompensationZ = CompensationZ; + this.throttle = throttle; + this.interference = interference; + + } + + /// packet xml order + public static mavlink_compassmot_status_t PopulateXMLOrder(ushort throttle,float current,ushort interference,float CompensationX,float CompensationY,float CompensationZ) + { + var msg = new mavlink_compassmot_status_t(); + + msg.throttle = throttle; + msg.current = current; + msg.interference = interference; + msg.CompensationX = CompensationX; + msg.CompensationY = CompensationY; + msg.CompensationZ = CompensationZ; + + return msg; + } + + + /// Current. [A] + [Units("[A]")] + [Description("Current.")] + //[FieldOffset(0)] + public float current; + + /// Motor Compensation X. + [Units("")] + [Description("Motor Compensation X.")] + //[FieldOffset(4)] + public float CompensationX; + + /// Motor Compensation Y. + [Units("")] + [Description("Motor Compensation Y.")] + //[FieldOffset(8)] + public float CompensationY; + + /// Motor Compensation Z. + [Units("")] + [Description("Motor Compensation Z.")] + //[FieldOffset(12)] + public float CompensationZ; + + /// Throttle. [d%] + [Units("[d%]")] + [Description("Throttle.")] + //[FieldOffset(16)] + public ushort throttle; + + /// Interference. [%] + [Units("[%]")] + [Description("Interference.")] + //[FieldOffset(18)] + public ushort interference; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// Status of secondary AHRS filter if available. + public struct mavlink_ahrs2_t + { + /// packet ordered constructor + public mavlink_ahrs2_t(float roll,float pitch,float yaw,float altitude,int lat,int lng) + { + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.altitude = altitude; + this.lat = lat; + this.lng = lng; + + } + + /// packet xml order + public static mavlink_ahrs2_t PopulateXMLOrder(float roll,float pitch,float yaw,float altitude,int lat,int lng) + { + var msg = new mavlink_ahrs2_t(); + + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.altitude = altitude; + msg.lat = lat; + msg.lng = lng; + + return msg; + } + + + /// Roll angle. [rad] + [Units("[rad]")] + [Description("Roll angle.")] + //[FieldOffset(0)] + public float roll; + + /// Pitch angle. [rad] + [Units("[rad]")] + [Description("Pitch angle.")] + //[FieldOffset(4)] + public float pitch; + + /// Yaw angle. [rad] + [Units("[rad]")] + [Description("Yaw angle.")] + //[FieldOffset(8)] + public float yaw; + + /// Altitude (MSL). [m] + [Units("[m]")] + [Description("Altitude (MSL).")] + //[FieldOffset(12)] + public float altitude; + + /// Latitude. [degE7] + [Units("[degE7]")] + [Description("Latitude.")] + //[FieldOffset(16)] + public int lat; + + /// Longitude. [degE7] + [Units("[degE7]")] + [Description("Longitude.")] + //[FieldOffset(20)] + public int lng; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=29)] + /// Camera Event. + public struct mavlink_camera_status_t + { + /// packet ordered constructor + public mavlink_camera_status_t(ulong time_usec,float p1,float p2,float p3,float p4,ushort img_idx,byte target_system,byte cam_idx,/*CAMERA_STATUS_TYPES*/byte event_id) + { + this.time_usec = time_usec; + this.p1 = p1; + this.p2 = p2; + this.p3 = p3; + this.p4 = p4; + this.img_idx = img_idx; + this.target_system = target_system; + this.cam_idx = cam_idx; + this.event_id = event_id; + + } + + /// packet xml order + public static mavlink_camera_status_t PopulateXMLOrder(ulong time_usec,byte target_system,byte cam_idx,ushort img_idx,/*CAMERA_STATUS_TYPES*/byte event_id,float p1,float p2,float p3,float p4) + { + var msg = new mavlink_camera_status_t(); + + msg.time_usec = time_usec; + msg.target_system = target_system; + msg.cam_idx = cam_idx; + msg.img_idx = img_idx; + msg.event_id = event_id; + msg.p1 = p1; + msg.p2 = p2; + msg.p3 = p3; + msg.p4 = p4; + + return msg; + } + + + /// Image timestamp (since UNIX epoch, according to camera clock). [us] + [Units("[us]")] + [Description("Image timestamp (since UNIX epoch, according to camera clock).")] + //[FieldOffset(0)] + public ulong time_usec; + + /// Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + [Units("")] + [Description("Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + //[FieldOffset(8)] + public float p1; + + /// Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + [Units("")] + [Description("Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + //[FieldOffset(12)] + public float p2; + + /// Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + [Units("")] + [Description("Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + //[FieldOffset(16)] + public float p3; + + /// Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + [Units("")] + [Description("Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + //[FieldOffset(20)] + public float p4; + + /// Image index. + [Units("")] + [Description("Image index.")] + //[FieldOffset(24)] + public ushort img_idx; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(26)] + public byte target_system; + + /// Camera ID. + [Units("")] + [Description("Camera ID.")] + //[FieldOffset(27)] + public byte cam_idx; + + /// Event type. CAMERA_STATUS_TYPES + [Units("")] + [Description("Event type.")] + //[FieldOffset(28)] + public /*CAMERA_STATUS_TYPES*/byte event_id; + }; + + + /// extensions_start 13 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=47)] + /// Camera Capture Feedback. + public struct mavlink_camera_feedback_t + { + /// packet ordered constructor + public mavlink_camera_feedback_t(ulong time_usec,int lat,int lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,ushort img_idx,byte target_system,byte cam_idx,/*CAMERA_FEEDBACK_FLAGS*/byte flags,ushort completed_captures) + { + this.time_usec = time_usec; + this.lat = lat; + this.lng = lng; + this.alt_msl = alt_msl; + this.alt_rel = alt_rel; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.foc_len = foc_len; + this.img_idx = img_idx; + this.target_system = target_system; + this.cam_idx = cam_idx; + this.flags = flags; + this.completed_captures = completed_captures; + + } + + /// packet xml order + public static mavlink_camera_feedback_t PopulateXMLOrder(ulong time_usec,byte target_system,byte cam_idx,ushort img_idx,int lat,int lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,/*CAMERA_FEEDBACK_FLAGS*/byte flags,ushort completed_captures) + { + var msg = new mavlink_camera_feedback_t(); + + msg.time_usec = time_usec; + msg.target_system = target_system; + msg.cam_idx = cam_idx; + msg.img_idx = img_idx; + msg.lat = lat; + msg.lng = lng; + msg.alt_msl = alt_msl; + msg.alt_rel = alt_rel; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.foc_len = foc_len; + msg.flags = flags; + msg.completed_captures = completed_captures; + + return msg; + } + + + /// Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB). [us] + [Units("[us]")] + [Description("Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).")] + //[FieldOffset(0)] + public ulong time_usec; + + /// Latitude. [degE7] + [Units("[degE7]")] + [Description("Latitude.")] + //[FieldOffset(8)] + public int lat; + + /// Longitude. [degE7] + [Units("[degE7]")] + [Description("Longitude.")] + //[FieldOffset(12)] + public int lng; + + /// Altitude (MSL). [m] + [Units("[m]")] + [Description("Altitude (MSL).")] + //[FieldOffset(16)] + public float alt_msl; + + /// Altitude (Relative to HOME location). [m] + [Units("[m]")] + [Description("Altitude (Relative to HOME location).")] + //[FieldOffset(20)] + public float alt_rel; + + /// Camera Roll angle (earth frame, +-180). [deg] + [Units("[deg]")] + [Description("Camera Roll angle (earth frame, +-180).")] + //[FieldOffset(24)] + public float roll; + + /// Camera Pitch angle (earth frame, +-180). [deg] + [Units("[deg]")] + [Description("Camera Pitch angle (earth frame, +-180).")] + //[FieldOffset(28)] + public float pitch; + + /// Camera Yaw (earth frame, 0-360, true). [deg] + [Units("[deg]")] + [Description("Camera Yaw (earth frame, 0-360, true).")] + //[FieldOffset(32)] + public float yaw; + + /// Focal Length. [mm] + [Units("[mm]")] + [Description("Focal Length.")] + //[FieldOffset(36)] + public float foc_len; + + /// Image index. + [Units("")] + [Description("Image index.")] + //[FieldOffset(40)] + public ushort img_idx; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(42)] + public byte target_system; + + /// Camera ID. + [Units("")] + [Description("Camera ID.")] + //[FieldOffset(43)] + public byte cam_idx; + + /// Feedback flags. CAMERA_FEEDBACK_FLAGS + [Units("")] + [Description("Feedback flags.")] + //[FieldOffset(44)] + public /*CAMERA_FEEDBACK_FLAGS*/byte flags; + + /// Completed image captures. + [Units("")] + [Description("Completed image captures.")] + //[FieldOffset(45)] + public ushort completed_captures; + }; + + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// 2nd Battery status + public struct mavlink_battery2_t + { + /// packet ordered constructor + public mavlink_battery2_t(ushort voltage,short current_battery) + { + this.voltage = voltage; + this.current_battery = current_battery; + + } + + /// packet xml order + public static mavlink_battery2_t PopulateXMLOrder(ushort voltage,short current_battery) + { + var msg = new mavlink_battery2_t(); + + msg.voltage = voltage; + msg.current_battery = current_battery; + + return msg; + } + + + /// Voltage. [mV] + [Units("[mV]")] + [Description("Voltage.")] + //[FieldOffset(0)] + public ushort voltage; + + /// Battery current, -1: autopilot does not measure the current. [cA] + [Units("[cA]")] + [Description("Battery current, -1: autopilot does not measure the current.")] + //[FieldOffset(2)] + public short current_battery; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] + /// Status of third AHRS filter if available. This is for ANU research group (Ali and Sean). + public struct mavlink_ahrs3_t + { + /// packet ordered constructor + public mavlink_ahrs3_t(float roll,float pitch,float yaw,float altitude,int lat,int lng,float v1,float v2,float v3,float v4) + { + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.altitude = altitude; + this.lat = lat; + this.lng = lng; + this.v1 = v1; + this.v2 = v2; + this.v3 = v3; + this.v4 = v4; + + } + + /// packet xml order + public static mavlink_ahrs3_t PopulateXMLOrder(float roll,float pitch,float yaw,float altitude,int lat,int lng,float v1,float v2,float v3,float v4) + { + var msg = new mavlink_ahrs3_t(); + + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.altitude = altitude; + msg.lat = lat; + msg.lng = lng; + msg.v1 = v1; + msg.v2 = v2; + msg.v3 = v3; + msg.v4 = v4; + + return msg; + } + + + /// Roll angle. [rad] + [Units("[rad]")] + [Description("Roll angle.")] + //[FieldOffset(0)] + public float roll; + + /// Pitch angle. [rad] + [Units("[rad]")] + [Description("Pitch angle.")] + //[FieldOffset(4)] + public float pitch; + + /// Yaw angle. [rad] + [Units("[rad]")] + [Description("Yaw angle.")] + //[FieldOffset(8)] + public float yaw; + + /// Altitude (MSL). [m] + [Units("[m]")] + [Description("Altitude (MSL).")] + //[FieldOffset(12)] + public float altitude; + + /// Latitude. [degE7] + [Units("[degE7]")] + [Description("Latitude.")] + //[FieldOffset(16)] + public int lat; + + /// Longitude. [degE7] + [Units("[degE7]")] + [Description("Longitude.")] + //[FieldOffset(20)] + public int lng; + + /// Test variable1. + [Units("")] + [Description("Test variable1.")] + //[FieldOffset(24)] + public float v1; + + /// Test variable2. + [Units("")] + [Description("Test variable2.")] + //[FieldOffset(28)] + public float v2; + + /// Test variable3. + [Units("")] + [Description("Test variable3.")] + //[FieldOffset(32)] + public float v3; + + /// Test variable4. + [Units("")] + [Description("Test variable4.")] + //[FieldOffset(36)] + public float v4; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Request the autopilot version from the system/component. + public struct mavlink_autopilot_version_request_t + { + /// packet ordered constructor + public mavlink_autopilot_version_request_t(byte target_system,byte target_component) + { + this.target_system = target_system; + this.target_component = target_component; + + } + + /// packet xml order + public static mavlink_autopilot_version_request_t PopulateXMLOrder(byte target_system,byte target_component) + { + var msg = new mavlink_autopilot_version_request_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=206)] + /// Send a block of log data to remote location. + public struct mavlink_remote_log_data_block_t + { + /// packet ordered constructor + public mavlink_remote_log_data_block_t(/*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS*/uint seqno,byte target_system,byte target_component,byte[] data) + { + this.seqno = seqno; + this.target_system = target_system; + this.target_component = target_component; + this.data = data; + + } + + /// packet xml order + public static mavlink_remote_log_data_block_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS*/uint seqno,byte[] data) + { + var msg = new mavlink_remote_log_data_block_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.seqno = seqno; + msg.data = data; + + return msg; + } + + + /// Log data block sequence number. MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS + [Units("")] + [Description("Log data block sequence number.")] + //[FieldOffset(0)] + public /*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS*/uint seqno; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(4)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; + + /// Log data block. + [Units("")] + [Description("Log data block.")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=200)] + public byte[] data; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] + /// Send Status of each log block that autopilot board might have sent. + public struct mavlink_remote_log_block_status_t + { + /// packet ordered constructor + public mavlink_remote_log_block_status_t(uint seqno,byte target_system,byte target_component,/*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES*/byte status) + { + this.seqno = seqno; + this.target_system = target_system; + this.target_component = target_component; + this.status = status; + + } + + /// packet xml order + public static mavlink_remote_log_block_status_t PopulateXMLOrder(byte target_system,byte target_component,uint seqno,/*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES*/byte status) + { + var msg = new mavlink_remote_log_block_status_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.seqno = seqno; + msg.status = status; + + return msg; + } + + + /// Log data block sequence number. + [Units("")] + [Description("Log data block sequence number.")] + //[FieldOffset(0)] + public uint seqno; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(4)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; + + /// Log data block status. MAV_REMOTE_LOG_DATA_BLOCK_STATUSES + [Units("")] + [Description("Log data block status.")] + //[FieldOffset(6)] + public /*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES*/byte status; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=29)] + /// Control vehicle LEDs. + public struct mavlink_led_control_t + { + /// packet ordered constructor + public mavlink_led_control_t(byte target_system,byte target_component,byte instance,byte pattern,byte custom_len,byte[] custom_bytes) + { + this.target_system = target_system; + this.target_component = target_component; + this.instance = instance; + this.pattern = pattern; + this.custom_len = custom_len; + this.custom_bytes = custom_bytes; + + } + + /// packet xml order + public static mavlink_led_control_t PopulateXMLOrder(byte target_system,byte target_component,byte instance,byte pattern,byte custom_len,byte[] custom_bytes) + { + var msg = new mavlink_led_control_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.instance = instance; + msg.pattern = pattern; + msg.custom_len = custom_len; + msg.custom_bytes = custom_bytes; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + + /// Instance (LED instance to control or 255 for all LEDs). + [Units("")] + [Description("Instance (LED instance to control or 255 for all LEDs).")] + //[FieldOffset(2)] + public byte instance; + + /// Pattern (see LED_PATTERN_ENUM). + [Units("")] + [Description("Pattern (see LED_PATTERN_ENUM).")] + //[FieldOffset(3)] + public byte pattern; + + /// Custom Byte Length. + [Units("")] + [Description("Custom Byte Length.")] + //[FieldOffset(4)] + public byte custom_len; + + /// Custom Bytes. + [Units("")] + [Description("Custom Bytes.")] + //[FieldOffset(5)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=24)] + public byte[] custom_bytes; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)] + /// Reports progress of compass calibration. + public struct mavlink_mag_cal_progress_t + { + /// packet ordered constructor + public mavlink_mag_cal_progress_t(float direction_x,float direction_y,float direction_z,byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte attempt,byte completion_pct,byte[] completion_mask) + { + this.direction_x = direction_x; + this.direction_y = direction_y; + this.direction_z = direction_z; + this.compass_id = compass_id; + this.cal_mask = cal_mask; + this.cal_status = cal_status; + this.attempt = attempt; + this.completion_pct = completion_pct; + this.completion_mask = completion_mask; + + } + + /// packet xml order + public static mavlink_mag_cal_progress_t PopulateXMLOrder(byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte attempt,byte completion_pct,byte[] completion_mask,float direction_x,float direction_y,float direction_z) + { + var msg = new mavlink_mag_cal_progress_t(); + + msg.compass_id = compass_id; + msg.cal_mask = cal_mask; + msg.cal_status = cal_status; + msg.attempt = attempt; + msg.completion_pct = completion_pct; + msg.completion_mask = completion_mask; + msg.direction_x = direction_x; + msg.direction_y = direction_y; + msg.direction_z = direction_z; + + return msg; + } + + + /// Body frame direction vector for display. + [Units("")] + [Description("Body frame direction vector for display.")] + //[FieldOffset(0)] + public float direction_x; + + /// Body frame direction vector for display. + [Units("")] + [Description("Body frame direction vector for display.")] + //[FieldOffset(4)] + public float direction_y; + + /// Body frame direction vector for display. + [Units("")] + [Description("Body frame direction vector for display.")] + //[FieldOffset(8)] + public float direction_z; + + /// Compass being calibrated. + [Units("")] + [Description("Compass being calibrated.")] + //[FieldOffset(12)] + public byte compass_id; + + /// Bitmask of compasses being calibrated. bitmask + [Units("")] + [Description("Bitmask of compasses being calibrated.")] + //[FieldOffset(13)] + public byte cal_mask; + + /// Calibration Status. MAG_CAL_STATUS + [Units("")] + [Description("Calibration Status.")] + //[FieldOffset(14)] + public /*MAG_CAL_STATUS*/byte cal_status; + + /// Attempt number. + [Units("")] + [Description("Attempt number.")] + //[FieldOffset(15)] + public byte attempt; + + /// Completion percentage. [%] + [Units("[%]")] + [Description("Completion percentage.")] + //[FieldOffset(16)] + public byte completion_pct; + + /// Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid). + [Units("")] + [Description("Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).")] + //[FieldOffset(17)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public byte[] completion_mask; + }; + + + /// extensions_start 6 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] + /// EKF Status message including flags and variances. + public struct mavlink_ekf_status_report_t + { + /// packet ordered constructor + public mavlink_ekf_status_report_t(float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,/*EKF_STATUS_FLAGS*/ushort flags,float airspeed_variance) + { + this.velocity_variance = velocity_variance; + this.pos_horiz_variance = pos_horiz_variance; + this.pos_vert_variance = pos_vert_variance; + this.compass_variance = compass_variance; + this.terrain_alt_variance = terrain_alt_variance; + this.flags = flags; + this.airspeed_variance = airspeed_variance; + + } + + /// packet xml order + public static mavlink_ekf_status_report_t PopulateXMLOrder(/*EKF_STATUS_FLAGS*/ushort flags,float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,float airspeed_variance) + { + var msg = new mavlink_ekf_status_report_t(); + + msg.flags = flags; + msg.velocity_variance = velocity_variance; + msg.pos_horiz_variance = pos_horiz_variance; + msg.pos_vert_variance = pos_vert_variance; + msg.compass_variance = compass_variance; + msg.terrain_alt_variance = terrain_alt_variance; + msg.airspeed_variance = airspeed_variance; + + return msg; + } + + + /// Velocity variance. + [Units("")] + [Description("Velocity variance.")] + //[FieldOffset(0)] + public float velocity_variance; + + /// Horizontal Position variance. + [Units("")] + [Description("Horizontal Position variance.")] + //[FieldOffset(4)] + public float pos_horiz_variance; + + /// Vertical Position variance. + [Units("")] + [Description("Vertical Position variance.")] + //[FieldOffset(8)] + public float pos_vert_variance; + + /// Compass variance. + [Units("")] + [Description("Compass variance.")] + //[FieldOffset(12)] + public float compass_variance; + + /// Terrain Altitude variance. + [Units("")] + [Description("Terrain Altitude variance.")] + //[FieldOffset(16)] + public float terrain_alt_variance; + + /// Flags. EKF_STATUS_FLAGS bitmask + [Units("")] + [Description("Flags.")] + //[FieldOffset(20)] + public /*EKF_STATUS_FLAGS*/ushort flags; + + /// Airspeed variance. + [Units("")] + [Description("Airspeed variance.")] + //[FieldOffset(22)] + public float airspeed_variance; + }; + + + /// extensions_start 7 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// PID tuning information. + public struct mavlink_pid_tuning_t + { + /// packet ordered constructor + public mavlink_pid_tuning_t(float desired,float achieved,float FF,float P,float I,float D,/*PID_TUNING_AXIS*/byte axis,float SRate,float PDmod) + { + this.desired = desired; + this.achieved = achieved; + this.FF = FF; + this.P = P; + this.I = I; + this.D = D; + this.axis = axis; + this.SRate = SRate; + this.PDmod = PDmod; + + } + + /// packet xml order + public static mavlink_pid_tuning_t PopulateXMLOrder(/*PID_TUNING_AXIS*/byte axis,float desired,float achieved,float FF,float P,float I,float D,float SRate,float PDmod) + { + var msg = new mavlink_pid_tuning_t(); + + msg.axis = axis; + msg.desired = desired; + msg.achieved = achieved; + msg.FF = FF; + msg.P = P; + msg.I = I; + msg.D = D; + msg.SRate = SRate; + msg.PDmod = PDmod; + + return msg; + } + + + /// Desired rate. + [Units("")] + [Description("Desired rate.")] + //[FieldOffset(0)] + public float desired; + + /// Achieved rate. + [Units("")] + [Description("Achieved rate.")] + //[FieldOffset(4)] + public float achieved; + + /// FF component. + [Units("")] + [Description("FF component.")] + //[FieldOffset(8)] + public float FF; + + /// P component. + [Units("")] + [Description("P component.")] + //[FieldOffset(12)] + public float P; + + /// I component. + [Units("")] + [Description("I component.")] + //[FieldOffset(16)] + public float I; + + /// D component. + [Units("")] + [Description("D component.")] + //[FieldOffset(20)] + public float D; + + /// Axis. PID_TUNING_AXIS + [Units("")] + [Description("Axis.")] + //[FieldOffset(24)] + public /*PID_TUNING_AXIS*/byte axis; + + /// Slew rate. + [Units("")] + [Description("Slew rate.")] + //[FieldOffset(25)] + public float SRate; + + /// P/D oscillation modifier. + [Units("")] + [Description("P/D oscillation modifier.")] + //[FieldOffset(29)] + public float PDmod; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] + /// Deepstall path planning. + public struct mavlink_deepstall_t + { + /// packet ordered constructor + public mavlink_deepstall_t(int landing_lat,int landing_lon,int path_lat,int path_lon,int arc_entry_lat,int arc_entry_lon,float altitude,float expected_travel_distance,float cross_track_error,/*DEEPSTALL_STAGE*/byte stage) + { + this.landing_lat = landing_lat; + this.landing_lon = landing_lon; + this.path_lat = path_lat; + this.path_lon = path_lon; + this.arc_entry_lat = arc_entry_lat; + this.arc_entry_lon = arc_entry_lon; + this.altitude = altitude; + this.expected_travel_distance = expected_travel_distance; + this.cross_track_error = cross_track_error; + this.stage = stage; + + } + + /// packet xml order + public static mavlink_deepstall_t PopulateXMLOrder(int landing_lat,int landing_lon,int path_lat,int path_lon,int arc_entry_lat,int arc_entry_lon,float altitude,float expected_travel_distance,float cross_track_error,/*DEEPSTALL_STAGE*/byte stage) + { + var msg = new mavlink_deepstall_t(); + + msg.landing_lat = landing_lat; + msg.landing_lon = landing_lon; + msg.path_lat = path_lat; + msg.path_lon = path_lon; + msg.arc_entry_lat = arc_entry_lat; + msg.arc_entry_lon = arc_entry_lon; + msg.altitude = altitude; + msg.expected_travel_distance = expected_travel_distance; + msg.cross_track_error = cross_track_error; + msg.stage = stage; + + return msg; + } + + + /// Landing latitude. [degE7] + [Units("[degE7]")] + [Description("Landing latitude.")] + //[FieldOffset(0)] + public int landing_lat; + + /// Landing longitude. [degE7] + [Units("[degE7]")] + [Description("Landing longitude.")] + //[FieldOffset(4)] + public int landing_lon; + + /// Final heading start point, latitude. [degE7] + [Units("[degE7]")] + [Description("Final heading start point, latitude.")] + //[FieldOffset(8)] + public int path_lat; + + /// Final heading start point, longitude. [degE7] + [Units("[degE7]")] + [Description("Final heading start point, longitude.")] + //[FieldOffset(12)] + public int path_lon; + + /// Arc entry point, latitude. [degE7] + [Units("[degE7]")] + [Description("Arc entry point, latitude.")] + //[FieldOffset(16)] + public int arc_entry_lat; + + /// Arc entry point, longitude. [degE7] + [Units("[degE7]")] + [Description("Arc entry point, longitude.")] + //[FieldOffset(20)] + public int arc_entry_lon; + + /// Altitude. [m] + [Units("[m]")] + [Description("Altitude.")] + //[FieldOffset(24)] + public float altitude; + + /// Distance the aircraft expects to travel during the deepstall. [m] + [Units("[m]")] + [Description("Distance the aircraft expects to travel during the deepstall.")] + //[FieldOffset(28)] + public float expected_travel_distance; + + /// Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND). [m] + [Units("[m]")] + [Description("Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).")] + //[FieldOffset(32)] + public float cross_track_error; + + /// Deepstall stage. DEEPSTALL_STAGE + [Units("")] + [Description("Deepstall stage.")] + //[FieldOffset(36)] + public /*DEEPSTALL_STAGE*/byte stage; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// 3 axis gimbal measurements. + public struct mavlink_gimbal_report_t + { + /// packet ordered constructor + public mavlink_gimbal_report_t(float delta_time,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_el,float joint_az,byte target_system,byte target_component) + { + this.delta_time = delta_time; + this.delta_angle_x = delta_angle_x; + this.delta_angle_y = delta_angle_y; + this.delta_angle_z = delta_angle_z; + this.delta_velocity_x = delta_velocity_x; + this.delta_velocity_y = delta_velocity_y; + this.delta_velocity_z = delta_velocity_z; + this.joint_roll = joint_roll; + this.joint_el = joint_el; + this.joint_az = joint_az; + this.target_system = target_system; + this.target_component = target_component; + + } + + /// packet xml order + public static mavlink_gimbal_report_t PopulateXMLOrder(byte target_system,byte target_component,float delta_time,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_el,float joint_az) + { + var msg = new mavlink_gimbal_report_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.delta_time = delta_time; + msg.delta_angle_x = delta_angle_x; + msg.delta_angle_y = delta_angle_y; + msg.delta_angle_z = delta_angle_z; + msg.delta_velocity_x = delta_velocity_x; + msg.delta_velocity_y = delta_velocity_y; + msg.delta_velocity_z = delta_velocity_z; + msg.joint_roll = joint_roll; + msg.joint_el = joint_el; + msg.joint_az = joint_az; + + return msg; + } + + + /// Time since last update. [s] + [Units("[s]")] + [Description("Time since last update.")] + //[FieldOffset(0)] + public float delta_time; + + /// Delta angle X. [rad] + [Units("[rad]")] + [Description("Delta angle X.")] + //[FieldOffset(4)] + public float delta_angle_x; + + /// Delta angle Y. [rad] + [Units("[rad]")] + [Description("Delta angle Y.")] + //[FieldOffset(8)] + public float delta_angle_y; + + /// Delta angle X. [rad] + [Units("[rad]")] + [Description("Delta angle X.")] + //[FieldOffset(12)] + public float delta_angle_z; + + /// Delta velocity X. [m/s] + [Units("[m/s]")] + [Description("Delta velocity X.")] + //[FieldOffset(16)] + public float delta_velocity_x; + + /// Delta velocity Y. [m/s] + [Units("[m/s]")] + [Description("Delta velocity Y.")] + //[FieldOffset(20)] + public float delta_velocity_y; + + /// Delta velocity Z. [m/s] + [Units("[m/s]")] + [Description("Delta velocity Z.")] + //[FieldOffset(24)] + public float delta_velocity_z; + + /// Joint ROLL. [rad] + [Units("[rad]")] + [Description("Joint ROLL.")] + //[FieldOffset(28)] + public float joint_roll; + + /// Joint EL. [rad] + [Units("[rad]")] + [Description("Joint EL.")] + //[FieldOffset(32)] + public float joint_el; + + /// Joint AZ. [rad] + [Units("[rad]")] + [Description("Joint AZ.")] + //[FieldOffset(36)] + public float joint_az; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(40)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(41)] + public byte target_component; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// Control message for rate gimbal. + public struct mavlink_gimbal_control_t + { + /// packet ordered constructor + public mavlink_gimbal_control_t(float demanded_rate_x,float demanded_rate_y,float demanded_rate_z,byte target_system,byte target_component) + { + this.demanded_rate_x = demanded_rate_x; + this.demanded_rate_y = demanded_rate_y; + this.demanded_rate_z = demanded_rate_z; + this.target_system = target_system; + this.target_component = target_component; + + } + + /// packet xml order + public static mavlink_gimbal_control_t PopulateXMLOrder(byte target_system,byte target_component,float demanded_rate_x,float demanded_rate_y,float demanded_rate_z) + { + var msg = new mavlink_gimbal_control_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.demanded_rate_x = demanded_rate_x; + msg.demanded_rate_y = demanded_rate_y; + msg.demanded_rate_z = demanded_rate_z; + + return msg; + } + + + /// Demanded angular rate X. [rad/s] + [Units("[rad/s]")] + [Description("Demanded angular rate X.")] + //[FieldOffset(0)] + public float demanded_rate_x; + + /// Demanded angular rate Y. [rad/s] + [Units("[rad/s]")] + [Description("Demanded angular rate Y.")] + //[FieldOffset(4)] + public float demanded_rate_y; + + /// Demanded angular rate Z. [rad/s] + [Units("[rad/s]")] + [Description("Demanded angular rate Z.")] + //[FieldOffset(8)] + public float demanded_rate_z; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(12)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(13)] + public byte target_component; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// 100 Hz gimbal torque command telemetry. + public struct mavlink_gimbal_torque_cmd_report_t + { + /// packet ordered constructor + public mavlink_gimbal_torque_cmd_report_t(short rl_torque_cmd,short el_torque_cmd,short az_torque_cmd,byte target_system,byte target_component) + { + this.rl_torque_cmd = rl_torque_cmd; + this.el_torque_cmd = el_torque_cmd; + this.az_torque_cmd = az_torque_cmd; + this.target_system = target_system; + this.target_component = target_component; + + } + + /// packet xml order + public static mavlink_gimbal_torque_cmd_report_t PopulateXMLOrder(byte target_system,byte target_component,short rl_torque_cmd,short el_torque_cmd,short az_torque_cmd) + { + var msg = new mavlink_gimbal_torque_cmd_report_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.rl_torque_cmd = rl_torque_cmd; + msg.el_torque_cmd = el_torque_cmd; + msg.az_torque_cmd = az_torque_cmd; + + return msg; + } + + + /// Roll Torque Command. + [Units("")] + [Description("Roll Torque Command.")] + //[FieldOffset(0)] + public short rl_torque_cmd; + + /// Elevation Torque Command. + [Units("")] + [Description("Elevation Torque Command.")] + //[FieldOffset(2)] + public short el_torque_cmd; + + /// Azimuth Torque Command. + [Units("")] + [Description("Azimuth Torque Command.")] + //[FieldOffset(4)] + public short az_torque_cmd; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(6)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(7)] + public byte target_component; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Heartbeat from a HeroBus attached GoPro. + public struct mavlink_gopro_heartbeat_t + { + /// packet ordered constructor + public mavlink_gopro_heartbeat_t(/*GOPRO_HEARTBEAT_STATUS*/byte status,/*GOPRO_CAPTURE_MODE*/byte capture_mode,/*GOPRO_HEARTBEAT_FLAGS*/byte flags) + { + this.status = status; + this.capture_mode = capture_mode; + this.flags = flags; + + } + + /// packet xml order + public static mavlink_gopro_heartbeat_t PopulateXMLOrder(/*GOPRO_HEARTBEAT_STATUS*/byte status,/*GOPRO_CAPTURE_MODE*/byte capture_mode,/*GOPRO_HEARTBEAT_FLAGS*/byte flags) + { + var msg = new mavlink_gopro_heartbeat_t(); + + msg.status = status; + msg.capture_mode = capture_mode; + msg.flags = flags; + + return msg; + } + + + /// Status. GOPRO_HEARTBEAT_STATUS + [Units("")] + [Description("Status.")] + //[FieldOffset(0)] + public /*GOPRO_HEARTBEAT_STATUS*/byte status; + + /// Current capture mode. GOPRO_CAPTURE_MODE + [Units("")] + [Description("Current capture mode.")] + //[FieldOffset(1)] + public /*GOPRO_CAPTURE_MODE*/byte capture_mode; + + /// Additional status bits. GOPRO_HEARTBEAT_FLAGS bitmask + [Units("")] + [Description("Additional status bits.")] + //[FieldOffset(2)] + public /*GOPRO_HEARTBEAT_FLAGS*/byte flags; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Request a GOPRO_COMMAND response from the GoPro. + public struct mavlink_gopro_get_request_t + { + /// packet ordered constructor + public mavlink_gopro_get_request_t(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id) + { + this.target_system = target_system; + this.target_component = target_component; + this.cmd_id = cmd_id; + + } + + /// packet xml order + public static mavlink_gopro_get_request_t PopulateXMLOrder(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id) + { + var msg = new mavlink_gopro_get_request_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.cmd_id = cmd_id; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + + /// Command ID. GOPRO_COMMAND + [Units("")] + [Description("Command ID.")] + //[FieldOffset(2)] + public /*GOPRO_COMMAND*/byte cmd_id; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Response from a GOPRO_COMMAND get request. + public struct mavlink_gopro_get_response_t + { + /// packet ordered constructor + public mavlink_gopro_get_response_t(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status,byte[] value) + { + this.cmd_id = cmd_id; + this.status = status; + this.value = value; + + } + + /// packet xml order + public static mavlink_gopro_get_response_t PopulateXMLOrder(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status,byte[] value) + { + var msg = new mavlink_gopro_get_response_t(); + + msg.cmd_id = cmd_id; + msg.status = status; + msg.value = value; + + return msg; + } + + + /// Command ID. GOPRO_COMMAND + [Units("")] + [Description("Command ID.")] + //[FieldOffset(0)] + public /*GOPRO_COMMAND*/byte cmd_id; + + /// Status. GOPRO_REQUEST_STATUS + [Units("")] + [Description("Status.")] + //[FieldOffset(1)] + public /*GOPRO_REQUEST_STATUS*/byte status; + + /// Value. + [Units("")] + [Description("Value.")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] value; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] + /// Request to set a GOPRO_COMMAND with a desired. + public struct mavlink_gopro_set_request_t + { + /// packet ordered constructor + public mavlink_gopro_set_request_t(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id,byte[] value) + { + this.target_system = target_system; + this.target_component = target_component; + this.cmd_id = cmd_id; + this.value = value; + + } + + /// packet xml order + public static mavlink_gopro_set_request_t PopulateXMLOrder(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id,byte[] value) + { + var msg = new mavlink_gopro_set_request_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.cmd_id = cmd_id; + msg.value = value; + + return msg; + } + + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(0)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(1)] + public byte target_component; + + /// Command ID. GOPRO_COMMAND + [Units("")] + [Description("Command ID.")] + //[FieldOffset(2)] + public /*GOPRO_COMMAND*/byte cmd_id; + + /// Value. + [Units("")] + [Description("Value.")] + //[FieldOffset(3)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] value; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Response from a GOPRO_COMMAND set request. + public struct mavlink_gopro_set_response_t + { + /// packet ordered constructor + public mavlink_gopro_set_response_t(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status) + { + this.cmd_id = cmd_id; + this.status = status; + + } + + /// packet xml order + public static mavlink_gopro_set_response_t PopulateXMLOrder(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status) + { + var msg = new mavlink_gopro_set_response_t(); + + msg.cmd_id = cmd_id; + msg.status = status; + + return msg; + } + + + /// Command ID. GOPRO_COMMAND + [Units("")] + [Description("Command ID.")] + //[FieldOffset(0)] + public /*GOPRO_COMMAND*/byte cmd_id; + + /// Status. GOPRO_REQUEST_STATUS + [Units("")] + [Description("Status.")] + //[FieldOffset(1)] + public /*GOPRO_REQUEST_STATUS*/byte status; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// RPM sensor output. + public struct mavlink_rpm_t + { + /// packet ordered constructor + public mavlink_rpm_t(float rpm1,float rpm2) + { + this.rpm1 = rpm1; + this.rpm2 = rpm2; + + } + + /// packet xml order + public static mavlink_rpm_t PopulateXMLOrder(float rpm1,float rpm2) + { + var msg = new mavlink_rpm_t(); + + msg.rpm1 = rpm1; + msg.rpm2 = rpm2; + + return msg; + } + + + /// RPM Sensor1. + [Units("")] + [Description("RPM Sensor1.")] + //[FieldOffset(0)] + public float rpm1; + + /// RPM Sensor2. + [Units("")] + [Description("RPM Sensor2.")] + //[FieldOffset(4)] + public float rpm2; + }; + + + /// extensions_start 9 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] + /// Read registers for a device. + public struct mavlink_device_op_read_t + { + /// packet ordered constructor + public mavlink_device_op_read_t(uint request_id,byte target_system,byte target_component,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte bank) + { + this.request_id = request_id; + this.target_system = target_system; + this.target_component = target_component; + this.bustype = bustype; + this.bus = bus; + this.address = address; + this.busname = busname; + this.regstart = regstart; + this.count = count; + this.bank = bank; + + } + + /// packet xml order + public static mavlink_device_op_read_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte bank) + { + var msg = new mavlink_device_op_read_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.request_id = request_id; + msg.bustype = bustype; + msg.bus = bus; + msg.address = address; + msg.busname = busname; + msg.regstart = regstart; + msg.count = count; + msg.bank = bank; + + return msg; + } + + + /// Request ID - copied to reply. + [Units("")] + [Description("Request ID - copied to reply.")] + //[FieldOffset(0)] + public uint request_id; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(4)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; + + /// The bus type. DEVICE_OP_BUSTYPE + [Units("")] + [Description("The bus type.")] + //[FieldOffset(6)] + public /*DEVICE_OP_BUSTYPE*/byte bustype; + + /// Bus number. + [Units("")] + [Description("Bus number.")] + //[FieldOffset(7)] + public byte bus; + + /// Bus address. + [Units("")] + [Description("Bus address.")] + //[FieldOffset(8)] + public byte address; + + /// Name of device on bus (for SPI). + [Units("")] + [Description("Name of device on bus (for SPI).")] + //[FieldOffset(9)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=40)] + public byte[] busname; + + /// First register to read. + [Units("")] + [Description("First register to read.")] + //[FieldOffset(49)] + public byte regstart; + + /// Count of registers to read. + [Units("")] + [Description("Count of registers to read.")] + //[FieldOffset(50)] + public byte count; + + /// Bank number. + [Units("")] + [Description("Bank number.")] + //[FieldOffset(51)] + public byte bank; + }; + + + /// extensions_start 5 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=136)] + /// Read registers reply. + public struct mavlink_device_op_read_reply_t + { + /// packet ordered constructor + public mavlink_device_op_read_reply_t(uint request_id,byte result,byte regstart,byte count,byte[] data,byte bank) + { + this.request_id = request_id; + this.result = result; + this.regstart = regstart; + this.count = count; + this.data = data; + this.bank = bank; + + } + + /// packet xml order + public static mavlink_device_op_read_reply_t PopulateXMLOrder(uint request_id,byte result,byte regstart,byte count,byte[] data,byte bank) + { + var msg = new mavlink_device_op_read_reply_t(); + + msg.request_id = request_id; + msg.result = result; + msg.regstart = regstart; + msg.count = count; + msg.data = data; + msg.bank = bank; + + return msg; + } + + + /// Request ID - copied from request. + [Units("")] + [Description("Request ID - copied from request.")] + //[FieldOffset(0)] + public uint request_id; + + /// 0 for success, anything else is failure code. + [Units("")] + [Description("0 for success, anything else is failure code.")] + //[FieldOffset(4)] + public byte result; + + /// Starting register. + [Units("")] + [Description("Starting register.")] + //[FieldOffset(5)] + public byte regstart; + + /// Count of bytes read. + [Units("")] + [Description("Count of bytes read.")] + //[FieldOffset(6)] + public byte count; + + /// Reply data. + [Units("")] + [Description("Reply data.")] + //[FieldOffset(7)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] + public byte[] data; + + /// Bank number. + [Units("")] + [Description("Bank number.")] + //[FieldOffset(135)] + public byte bank; + }; + + + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=180)] + /// Write registers for a device. + public struct mavlink_device_op_write_t + { + /// packet ordered constructor + public mavlink_device_op_write_t(uint request_id,byte target_system,byte target_component,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte[] data,byte bank) + { + this.request_id = request_id; + this.target_system = target_system; + this.target_component = target_component; + this.bustype = bustype; + this.bus = bus; + this.address = address; + this.busname = busname; + this.regstart = regstart; + this.count = count; + this.data = data; + this.bank = bank; + + } + + /// packet xml order + public static mavlink_device_op_write_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte[] data,byte bank) + { + var msg = new mavlink_device_op_write_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.request_id = request_id; + msg.bustype = bustype; + msg.bus = bus; + msg.address = address; + msg.busname = busname; + msg.regstart = regstart; + msg.count = count; + msg.data = data; + msg.bank = bank; + + return msg; + } + + + /// Request ID - copied to reply. + [Units("")] + [Description("Request ID - copied to reply.")] + //[FieldOffset(0)] + public uint request_id; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(4)] + public byte target_system; + + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; + + /// The bus type. DEVICE_OP_BUSTYPE + [Units("")] + [Description("The bus type.")] + //[FieldOffset(6)] + public /*DEVICE_OP_BUSTYPE*/byte bustype; + + /// Bus number. + [Units("")] + [Description("Bus number.")] + //[FieldOffset(7)] + public byte bus; + + /// Bus address. + [Units("")] + [Description("Bus address.")] + //[FieldOffset(8)] + public byte address; + + /// Name of device on bus (for SPI). + [Units("")] + [Description("Name of device on bus (for SPI).")] + //[FieldOffset(9)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=40)] + public byte[] busname; + + /// First register to write. + [Units("")] + [Description("First register to write.")] + //[FieldOffset(49)] + public byte regstart; + + /// Count of registers to write. + [Units("")] + [Description("Count of registers to write.")] + //[FieldOffset(50)] + public byte count; + + /// Write data. + [Units("")] + [Description("Write data.")] + //[FieldOffset(51)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] + public byte[] data; + + /// Bank number. + [Units("")] + [Description("Bank number.")] + //[FieldOffset(179)] + public byte bank; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// Write registers reply. + public struct mavlink_device_op_write_reply_t + { + /// packet ordered constructor + public mavlink_device_op_write_reply_t(uint request_id,byte result) + { + this.request_id = request_id; + this.result = result; + + } + + /// packet xml order + public static mavlink_device_op_write_reply_t PopulateXMLOrder(uint request_id,byte result) + { + var msg = new mavlink_device_op_write_reply_t(); + + msg.request_id = request_id; + msg.result = result; + + return msg; + } + + + /// Request ID - copied from request. [Units("")] - [Description("Correspondent value to given extra_param.")] + [Description("Request ID - copied from request.")] //[FieldOffset(0)] - public float extra_value; + public uint request_id; - /// System ID. + /// 0 for success, anything else is failure code. [Units("")] - [Description("System ID.")] + [Description("0 for success, anything else is failure code.")] //[FieldOffset(4)] - public byte target_system; + public byte result; + }; - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=232)] + /// Send a secure command. Data should be signed with a private key corresponding with a public key known to the recipient. Signature should be over the concatenation of the sequence number (little-endian format), the operation (little-endian format) the data and the session key. For SECURE_COMMAND_GET_SESSION_KEY the session key should be zero length. The data array consists of the data followed by the signature. The sum of the data_length and the sig_length cannot be more than 220. The format of the data is command specific. + public struct mavlink_secure_command_t + { + /// packet ordered constructor + public mavlink_secure_command_t(uint sequence,/*SECURE_COMMAND_OP*/uint operation,byte target_system,byte target_component,byte data_length,byte sig_length,byte[] data) + { + this.sequence = sequence; + this.operation = operation; + this.target_system = target_system; + this.target_component = target_component; + this.data_length = data_length; + this.sig_length = sig_length; + this.data = data; + + } + + /// packet xml order + public static mavlink_secure_command_t PopulateXMLOrder(byte target_system,byte target_component,uint sequence,/*SECURE_COMMAND_OP*/uint operation,byte data_length,byte sig_length,byte[] data) + { + var msg = new mavlink_secure_command_t(); - /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens. + msg.target_system = target_system; + msg.target_component = target_component; + msg.sequence = sequence; + msg.operation = operation; + msg.data_length = data_length; + msg.sig_length = sig_length; + msg.data = data; + + return msg; + } + + + /// Sequence ID for tagging reply. [Units("")] - [Description("0: stop, 1: start or keep it up //Session control e.g. show/hide lens.")] - //[FieldOffset(6)] - public byte session; + [Description("Sequence ID for tagging reply.")] + //[FieldOffset(0)] + public uint sequence; - /// 1 to N //Zoom's absolute position (0 means ignore). + /// Operation being requested. SECURE_COMMAND_OP [Units("")] - [Description("1 to N //Zoom's absolute position (0 means ignore).")] - //[FieldOffset(7)] - public byte zoom_pos; + [Description("Operation being requested.")] + //[FieldOffset(4)] + public /*SECURE_COMMAND_OP*/uint operation; - /// -100 to 100 //Zooming step value to offset zoom from the current position. + /// System ID. [Units("")] - [Description("-100 to 100 //Zooming step value to offset zoom from the current position.")] + [Description("System ID.")] //[FieldOffset(8)] - public sbyte zoom_step; + public byte target_system; - /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus. + /// Component ID. [Units("")] - [Description("0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.")] + [Description("Component ID.")] //[FieldOffset(9)] - public byte focus_lock; + public byte target_component; - /// 0: ignore, 1: shot or start filming. + /// Data length. [Units("")] - [Description("0: ignore, 1: shot or start filming.")] + [Description("Data length.")] //[FieldOffset(10)] - public byte shot; + public byte data_length; - /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once. + /// Signature length. [Units("")] - [Description("Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.")] + [Description("Signature length.")] //[FieldOffset(11)] - public byte command_id; + public byte sig_length; - /// Extra parameters enumeration (0 means ignore). + /// Signed data. [Units("")] - [Description("Extra parameters enumeration (0 means ignore).")] + [Description("Signed data.")] //[FieldOffset(12)] - public byte extra_param; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=220)] + public byte[] data; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Message to configure a camera mount, directional antenna, etc. - public struct mavlink_mount_configure_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=230)] + /// Reply from secure command. + public struct mavlink_secure_command_reply_t { /// packet ordered constructor - public mavlink_mount_configure_t(byte target_system,byte target_component,/*MAV_MOUNT_MODE*/byte mount_mode,byte stab_roll,byte stab_pitch,byte stab_yaw) + public mavlink_secure_command_reply_t(uint sequence,/*SECURE_COMMAND_OP*/uint operation,/*MAV_RESULT*/byte result,byte data_length,byte[] data) { - this.target_system = target_system; - this.target_component = target_component; - this.mount_mode = mount_mode; - this.stab_roll = stab_roll; - this.stab_pitch = stab_pitch; - this.stab_yaw = stab_yaw; + this.sequence = sequence; + this.operation = operation; + this.result = result; + this.data_length = data_length; + this.data = data; } /// packet xml order - public static mavlink_mount_configure_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MOUNT_MODE*/byte mount_mode,byte stab_roll,byte stab_pitch,byte stab_yaw) + public static mavlink_secure_command_reply_t PopulateXMLOrder(uint sequence,/*SECURE_COMMAND_OP*/uint operation,/*MAV_RESULT*/byte result,byte data_length,byte[] data) { - var msg = new mavlink_mount_configure_t(); + var msg = new mavlink_secure_command_reply_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.mount_mode = mount_mode; - msg.stab_roll = stab_roll; - msg.stab_pitch = stab_pitch; - msg.stab_yaw = stab_yaw; + msg.sequence = sequence; + msg.operation = operation; + msg.result = result; + msg.data_length = data_length; + msg.data = data; return msg; } - /// System ID. + /// Sequence ID from request. [Units("")] - [Description("System ID.")] + [Description("Sequence ID from request.")] //[FieldOffset(0)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(1)] - public byte target_component; + public uint sequence; - /// Mount operating mode. MAV_MOUNT_MODE + /// Operation that was requested. SECURE_COMMAND_OP [Units("")] - [Description("Mount operating mode.")] - //[FieldOffset(2)] - public /*MAV_MOUNT_MODE*/byte mount_mode; + [Description("Operation that was requested.")] + //[FieldOffset(4)] + public /*SECURE_COMMAND_OP*/uint operation; - /// (1 = yes, 0 = no). + /// Result of command. MAV_RESULT [Units("")] - [Description("(1 = yes, 0 = no).")] - //[FieldOffset(3)] - public byte stab_roll; + [Description("Result of command.")] + //[FieldOffset(8)] + public /*MAV_RESULT*/byte result; - /// (1 = yes, 0 = no). + /// Data length. [Units("")] - [Description("(1 = yes, 0 = no).")] - //[FieldOffset(4)] - public byte stab_pitch; + [Description("Data length.")] + //[FieldOffset(9)] + public byte data_length; - /// (1 = yes, 0 = no). + /// Reply data. [Units("")] - [Description("(1 = yes, 0 = no).")] - //[FieldOffset(5)] - public byte stab_yaw; + [Description("Reply data.")] + //[FieldOffset(10)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=220)] + public byte[] data; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - /// Message to control a camera mount, directional antenna, etc. - public struct mavlink_mount_control_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=49)] + /// Adaptive Controller tuning information. + public struct mavlink_adap_tuning_t { /// packet ordered constructor - public mavlink_mount_control_t(int input_a,int input_b,int input_c,byte target_system,byte target_component,byte save_position) + public mavlink_adap_tuning_t(float desired,float achieved,float error,float theta,float omega,float sigma,float theta_dot,float omega_dot,float sigma_dot,float f,float f_dot,float u,/*PID_TUNING_AXIS*/byte axis) { - this.input_a = input_a; - this.input_b = input_b; - this.input_c = input_c; - this.target_system = target_system; - this.target_component = target_component; - this.save_position = save_position; + this.desired = desired; + this.achieved = achieved; + this.error = error; + this.theta = theta; + this.omega = omega; + this.sigma = sigma; + this.theta_dot = theta_dot; + this.omega_dot = omega_dot; + this.sigma_dot = sigma_dot; + this.f = f; + this.f_dot = f_dot; + this.u = u; + this.axis = axis; } /// packet xml order - public static mavlink_mount_control_t PopulateXMLOrder(byte target_system,byte target_component,int input_a,int input_b,int input_c,byte save_position) + public static mavlink_adap_tuning_t PopulateXMLOrder(/*PID_TUNING_AXIS*/byte axis,float desired,float achieved,float error,float theta,float omega,float sigma,float theta_dot,float omega_dot,float sigma_dot,float f,float f_dot,float u) { - var msg = new mavlink_mount_control_t(); + var msg = new mavlink_adap_tuning_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.input_a = input_a; - msg.input_b = input_b; - msg.input_c = input_c; - msg.save_position = save_position; + msg.axis = axis; + msg.desired = desired; + msg.achieved = achieved; + msg.error = error; + msg.theta = theta; + msg.omega = omega; + msg.sigma = sigma; + msg.theta_dot = theta_dot; + msg.omega_dot = omega_dot; + msg.sigma_dot = sigma_dot; + msg.f = f; + msg.f_dot = f_dot; + msg.u = u; return msg; } - /// Pitch (centi-degrees) or lat (degE7), depending on mount mode. - [Units("")] - [Description("Pitch (centi-degrees) or lat (degE7), depending on mount mode.")] + /// Desired rate. [deg/s] + [Units("[deg/s]")] + [Description("Desired rate.")] //[FieldOffset(0)] - public int input_a; + public float desired; - /// Roll (centi-degrees) or lon (degE7) depending on mount mode. - [Units("")] - [Description("Roll (centi-degrees) or lon (degE7) depending on mount mode.")] + /// Achieved rate. [deg/s] + [Units("[deg/s]")] + [Description("Achieved rate.")] //[FieldOffset(4)] - public int input_b; + public float achieved; - /// Yaw (centi-degrees) or alt (cm) depending on mount mode. + /// Error between model and vehicle. [Units("")] - [Description("Yaw (centi-degrees) or alt (cm) depending on mount mode.")] + [Description("Error between model and vehicle.")] //[FieldOffset(8)] - public int input_c; + public float error; - /// System ID. + /// Theta estimated state predictor. [Units("")] - [Description("System ID.")] + [Description("Theta estimated state predictor.")] //[FieldOffset(12)] - public byte target_system; + public float theta; - /// Component ID. + /// Omega estimated state predictor. [Units("")] - [Description("Component ID.")] - //[FieldOffset(13)] - public byte target_component; + [Description("Omega estimated state predictor.")] + //[FieldOffset(16)] + public float omega; + + /// Sigma estimated state predictor. + [Units("")] + [Description("Sigma estimated state predictor.")] + //[FieldOffset(20)] + public float sigma; + + /// Theta derivative. + [Units("")] + [Description("Theta derivative.")] + //[FieldOffset(24)] + public float theta_dot; + + /// Omega derivative. + [Units("")] + [Description("Omega derivative.")] + //[FieldOffset(28)] + public float omega_dot; + + /// Sigma derivative. + [Units("")] + [Description("Sigma derivative.")] + //[FieldOffset(32)] + public float sigma_dot; + + /// Projection operator value. + [Units("")] + [Description("Projection operator value.")] + //[FieldOffset(36)] + public float f; + + /// Projection operator derivative. + [Units("")] + [Description("Projection operator derivative.")] + //[FieldOffset(40)] + public float f_dot; + + /// u adaptive controlled output command. + [Units("")] + [Description("u adaptive controlled output command.")] + //[FieldOffset(44)] + public float u; + + /// Axis. PID_TUNING_AXIS + [Units("")] + [Description("Axis.")] + //[FieldOffset(48)] + public /*PID_TUNING_AXIS*/byte axis; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// Camera vision based attitude and position deltas. + public struct mavlink_vision_position_delta_t + { + /// packet ordered constructor + public mavlink_vision_position_delta_t(ulong time_usec,ulong time_delta_usec,float[] angle_delta,float[] position_delta,float confidence) + { + this.time_usec = time_usec; + this.time_delta_usec = time_delta_usec; + this.angle_delta = angle_delta; + this.position_delta = position_delta; + this.confidence = confidence; + + } + + /// packet xml order + public static mavlink_vision_position_delta_t PopulateXMLOrder(ulong time_usec,ulong time_delta_usec,float[] angle_delta,float[] position_delta,float confidence) + { + var msg = new mavlink_vision_position_delta_t(); + + msg.time_usec = time_usec; + msg.time_delta_usec = time_delta_usec; + msg.angle_delta = angle_delta; + msg.position_delta = position_delta; + msg.confidence = confidence; + + return msg; + } + + + /// Timestamp (synced to UNIX time or since system boot). [us] + [Units("[us]")] + [Description("Timestamp (synced to UNIX time or since system boot).")] + //[FieldOffset(0)] + public ulong time_usec; + + /// Time since the last reported camera frame. [us] + [Units("[us]")] + [Description("Time since the last reported camera frame.")] + //[FieldOffset(8)] + public ulong time_delta_usec; + + /// Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD. [rad] + [Units("[rad]")] + [Description("Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] angle_delta; + + /// Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD. [m] + [Units("[m]")] + [Description("Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.")] + //[FieldOffset(28)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] position_delta; + + /// Normalised confidence value from 0 to 100. [%] + [Units("[%]")] + [Description("Normalised confidence value from 0 to 100.")] + //[FieldOffset(40)] + public float confidence; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Angle of Attack and Side Slip Angle. + public struct mavlink_aoa_ssa_t + { + /// packet ordered constructor + public mavlink_aoa_ssa_t(ulong time_usec,float AOA,float SSA) + { + this.time_usec = time_usec; + this.AOA = AOA; + this.SSA = SSA; + + } + + /// packet xml order + public static mavlink_aoa_ssa_t PopulateXMLOrder(ulong time_usec,float AOA,float SSA) + { + var msg = new mavlink_aoa_ssa_t(); + + msg.time_usec = time_usec; + msg.AOA = AOA; + msg.SSA = SSA; + + return msg; + } + + + /// Timestamp (since boot or Unix epoch). [us] + [Units("[us]")] + [Description("Timestamp (since boot or Unix epoch).")] + //[FieldOffset(0)] + public ulong time_usec; + + /// Angle of Attack. [deg] + [Units("[deg]")] + [Description("Angle of Attack.")] + //[FieldOffset(8)] + public float AOA; + + /// Side Slip Angle. [deg] + [Units("[deg]")] + [Description("Side Slip Angle.")] + //[FieldOffset(12)] + public float SSA; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_1_to_4_t + { + /// packet ordered constructor + public mavlink_esc_telemetry_1_to_4_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + { + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; + + } + + /// packet xml order + public static mavlink_esc_telemetry_1_to_4_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + { + var msg = new mavlink_esc_telemetry_1_to_4_t(); + + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; + + return msg; + } + + + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; + + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; + + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; + + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; - /// If '1' it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING). + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("If '1' it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).")] - //[FieldOffset(14)] - public byte save_position; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; - /// extensions_start 5 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - /// Message with some status from autopilot to GCS about camera or antenna mount. - public struct mavlink_mount_status_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_5_to_8_t { /// packet ordered constructor - public mavlink_mount_status_t(int pointing_a,int pointing_b,int pointing_c,byte target_system,byte target_component,/*MAV_MOUNT_MODE*/byte mount_mode) + public mavlink_esc_telemetry_5_to_8_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.pointing_a = pointing_a; - this.pointing_b = pointing_b; - this.pointing_c = pointing_c; - this.target_system = target_system; - this.target_component = target_component; - this.mount_mode = mount_mode; + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_mount_status_t PopulateXMLOrder(byte target_system,byte target_component,int pointing_a,int pointing_b,int pointing_c,/*MAV_MOUNT_MODE*/byte mount_mode) + public static mavlink_esc_telemetry_5_to_8_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_mount_status_t(); + var msg = new mavlink_esc_telemetry_5_to_8_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.pointing_a = pointing_a; - msg.pointing_b = pointing_b; - msg.pointing_c = pointing_c; - msg.mount_mode = mount_mode; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; return msg; } - /// Pitch. [cdeg] - [Units("[cdeg]")] - [Description("Pitch.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public int pointing_a; - - /// Roll. [cdeg] - [Units("[cdeg]")] - [Description("Roll.")] - //[FieldOffset(4)] - public int pointing_b; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; - /// Yaw. [cdeg] - [Units("[cdeg]")] - [Description("Yaw.")] + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] //[FieldOffset(8)] - public int pointing_c; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(12)] - public byte target_system; + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(13)] - public byte target_component; + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; - /// Mount operating mode. MAV_MOUNT_MODE + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("Mount operating mode.")] - //[FieldOffset(14)] - public /*MAV_MOUNT_MODE*/byte mount_mode; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - /// A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS. - public struct mavlink_fence_point_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_9_to_12_t { /// packet ordered constructor - public mavlink_fence_point_t(float lat,float lng,byte target_system,byte target_component,byte idx,byte count) + public mavlink_esc_telemetry_9_to_12_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.lat = lat; - this.lng = lng; - this.target_system = target_system; - this.target_component = target_component; - this.idx = idx; + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_fence_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx,byte count,float lat,float lng) + public static mavlink_esc_telemetry_9_to_12_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_fence_point_t(); + var msg = new mavlink_esc_telemetry_9_to_12_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.idx = idx; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; msg.count = count; - msg.lat = lat; - msg.lng = lng; return msg; } - /// Latitude of point. [deg] - [Units("[deg]")] - [Description("Latitude of point.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public float lat; - - /// Longitude of point. [deg] - [Units("[deg]")] - [Description("Longitude of point.")] - //[FieldOffset(4)] - public float lng; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; - /// System ID. - [Units("")] - [Description("System ID.")] + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] //[FieldOffset(8)] - public byte target_system; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(9)] - public byte target_component; + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; - /// Point index (first point is 1, 0 is for return point). - [Units("")] - [Description("Point index (first point is 1, 0 is for return point).")] - //[FieldOffset(10)] - public byte idx; + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; - /// Total number of points (for sanity checking). + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("Total number of points (for sanity checking).")] - //[FieldOffset(11)] - public byte count; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Request a current fence point from MAV. - public struct mavlink_fence_fetch_point_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] + /// Configure an OSD parameter slot. + public struct mavlink_osd_param_config_t { /// packet ordered constructor - public mavlink_fence_fetch_point_t(byte target_system,byte target_component,byte idx) + public mavlink_osd_param_config_t(uint request_id,float min_value,float max_value,float increment,byte target_system,byte target_component,byte osd_screen,byte osd_index,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type) { + this.request_id = request_id; + this.min_value = min_value; + this.max_value = max_value; + this.increment = increment; this.target_system = target_system; this.target_component = target_component; - this.idx = idx; + this.osd_screen = osd_screen; + this.osd_index = osd_index; + this.param_id = param_id; + this.config_type = config_type; } /// packet xml order - public static mavlink_fence_fetch_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx) + public static mavlink_osd_param_config_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,byte osd_screen,byte osd_index,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type,float min_value,float max_value,float increment) { - var msg = new mavlink_fence_fetch_point_t(); + var msg = new mavlink_osd_param_config_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.idx = idx; + msg.request_id = request_id; + msg.osd_screen = osd_screen; + msg.osd_index = osd_index; + msg.param_id = param_id; + msg.config_type = config_type; + msg.min_value = min_value; + msg.max_value = max_value; + msg.increment = increment; return msg; } + /// Request ID - copied to reply. + [Units("")] + [Description("Request ID - copied to reply.")] + //[FieldOffset(0)] + public uint request_id; + + /// OSD parameter minimum value. + [Units("")] + [Description("OSD parameter minimum value.")] + //[FieldOffset(4)] + public float min_value; + + /// OSD parameter maximum value. + [Units("")] + [Description("OSD parameter maximum value.")] + //[FieldOffset(8)] + public float max_value; + + /// OSD parameter increment. + [Units("")] + [Description("OSD parameter increment.")] + //[FieldOffset(12)] + public float increment; + /// System ID. [Units("")] [Description("System ID.")] - //[FieldOffset(0)] + //[FieldOffset(16)] public byte target_system; /// Component ID. [Units("")] [Description("Component ID.")] - //[FieldOffset(1)] + //[FieldOffset(17)] public byte target_component; - /// Point index (first point is 1, 0 is for return point). + /// OSD parameter screen index. [Units("")] - [Description("Point index (first point is 1, 0 is for return point).")] - //[FieldOffset(2)] - public byte idx; + [Description("OSD parameter screen index.")] + //[FieldOffset(18)] + public byte osd_screen; + + /// OSD parameter display index. + [Units("")] + [Description("OSD parameter display index.")] + //[FieldOffset(19)] + public byte osd_index; + + /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + [Units("")] + [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; + + /// Config type. OSD_PARAM_CONFIG_TYPE + [Units("")] + [Description("Config type.")] + //[FieldOffset(36)] + public /*OSD_PARAM_CONFIG_TYPE*/byte config_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// Status of DCM attitude estimator. - public struct mavlink_ahrs_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// Configure OSD parameter reply. + public struct mavlink_osd_param_config_reply_t { /// packet ordered constructor - public mavlink_ahrs_t(float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) + public mavlink_osd_param_config_reply_t(uint request_id,/*OSD_PARAM_CONFIG_ERROR*/byte result) { - this.omegaIx = omegaIx; - this.omegaIy = omegaIy; - this.omegaIz = omegaIz; - this.accel_weight = accel_weight; - this.renorm_val = renorm_val; - this.error_rp = error_rp; - this.error_yaw = error_yaw; + this.request_id = request_id; + this.result = result; } /// packet xml order - public static mavlink_ahrs_t PopulateXMLOrder(float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) + public static mavlink_osd_param_config_reply_t PopulateXMLOrder(uint request_id,/*OSD_PARAM_CONFIG_ERROR*/byte result) { - var msg = new mavlink_ahrs_t(); + var msg = new mavlink_osd_param_config_reply_t(); - msg.omegaIx = omegaIx; - msg.omegaIy = omegaIy; - msg.omegaIz = omegaIz; - msg.accel_weight = accel_weight; - msg.renorm_val = renorm_val; - msg.error_rp = error_rp; - msg.error_yaw = error_yaw; + msg.request_id = request_id; + msg.result = result; return msg; } - /// X gyro drift estimate. [rad/s] - [Units("[rad/s]")] - [Description("X gyro drift estimate.")] - //[FieldOffset(0)] - public float omegaIx; - - /// Y gyro drift estimate. [rad/s] - [Units("[rad/s]")] - [Description("Y gyro drift estimate.")] - //[FieldOffset(4)] - public float omegaIy; - - /// Z gyro drift estimate. [rad/s] - [Units("[rad/s]")] - [Description("Z gyro drift estimate.")] - //[FieldOffset(8)] - public float omegaIz; - - /// Average accel_weight. - [Units("")] - [Description("Average accel_weight.")] - //[FieldOffset(12)] - public float accel_weight; - - /// Average renormalisation value. - [Units("")] - [Description("Average renormalisation value.")] - //[FieldOffset(16)] - public float renorm_val; - - /// Average error_roll_pitch value. + /// Request ID - copied from request. [Units("")] - [Description("Average error_roll_pitch value.")] - //[FieldOffset(20)] - public float error_rp; + [Description("Request ID - copied from request.")] + //[FieldOffset(0)] + public uint request_id; - /// Average error_yaw value. + /// Config error type. OSD_PARAM_CONFIG_ERROR [Units("")] - [Description("Average error_yaw value.")] - //[FieldOffset(24)] - public float error_yaw; + [Description("Config error type.")] + //[FieldOffset(4)] + public /*OSD_PARAM_CONFIG_ERROR*/byte result; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// Status of simulation environment, if used. - public struct mavlink_simstate_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Read a configured an OSD parameter slot. + public struct mavlink_osd_param_show_config_t { /// packet ordered constructor - public mavlink_simstate_t(float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int lat,int lng) + public mavlink_osd_param_show_config_t(uint request_id,byte target_system,byte target_component,byte osd_screen,byte osd_index) { - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.lat = lat; - this.lng = lng; + this.request_id = request_id; + this.target_system = target_system; + this.target_component = target_component; + this.osd_screen = osd_screen; + this.osd_index = osd_index; } /// packet xml order - public static mavlink_simstate_t PopulateXMLOrder(float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int lat,int lng) + public static mavlink_osd_param_show_config_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,byte osd_screen,byte osd_index) { - var msg = new mavlink_simstate_t(); + var msg = new mavlink_osd_param_show_config_t(); - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.lat = lat; - msg.lng = lng; + msg.target_system = target_system; + msg.target_component = target_component; + msg.request_id = request_id; + msg.osd_screen = osd_screen; + msg.osd_index = osd_index; return msg; } - /// Roll angle. [rad] - [Units("[rad]")] - [Description("Roll angle.")] + /// Request ID - copied to reply. + [Units("")] + [Description("Request ID - copied to reply.")] //[FieldOffset(0)] - public float roll; + public uint request_id; - /// Pitch angle. [rad] - [Units("[rad]")] - [Description("Pitch angle.")] + /// System ID. + [Units("")] + [Description("System ID.")] //[FieldOffset(4)] - public float pitch; - - /// Yaw angle. [rad] - [Units("[rad]")] - [Description("Yaw angle.")] - //[FieldOffset(8)] - public float yaw; - - /// X acceleration. [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration.")] - //[FieldOffset(12)] - public float xacc; - - /// Y acceleration. [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration.")] - //[FieldOffset(16)] - public float yacc; - - /// Z acceleration. [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration.")] - //[FieldOffset(20)] - public float zacc; - - /// Angular speed around X axis. [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around X axis.")] - //[FieldOffset(24)] - public float xgyro; - - /// Angular speed around Y axis. [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Y axis.")] - //[FieldOffset(28)] - public float ygyro; + public byte target_system; - /// Angular speed around Z axis. [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Z axis.")] - //[FieldOffset(32)] - public float zgyro; + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; - /// Latitude. [degE7] - [Units("[degE7]")] - [Description("Latitude.")] - //[FieldOffset(36)] - public int lat; + /// OSD parameter screen index. + [Units("")] + [Description("OSD parameter screen index.")] + //[FieldOffset(6)] + public byte osd_screen; - /// Longitude. [degE7] - [Units("[degE7]")] - [Description("Longitude.")] - //[FieldOffset(40)] - public int lng; + /// OSD parameter display index. + [Units("")] + [Description("OSD parameter display index.")] + //[FieldOffset(7)] + public byte osd_index; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Status of key hardware. - public struct mavlink_hwstatus_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] + /// Read configured OSD parameter reply. + public struct mavlink_osd_param_show_config_reply_t { /// packet ordered constructor - public mavlink_hwstatus_t(ushort Vcc,byte I2Cerr) + public mavlink_osd_param_show_config_reply_t(uint request_id,float min_value,float max_value,float increment,/*OSD_PARAM_CONFIG_ERROR*/byte result,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type) { - this.Vcc = Vcc; - this.I2Cerr = I2Cerr; + this.request_id = request_id; + this.min_value = min_value; + this.max_value = max_value; + this.increment = increment; + this.result = result; + this.param_id = param_id; + this.config_type = config_type; } /// packet xml order - public static mavlink_hwstatus_t PopulateXMLOrder(ushort Vcc,byte I2Cerr) + public static mavlink_osd_param_show_config_reply_t PopulateXMLOrder(uint request_id,/*OSD_PARAM_CONFIG_ERROR*/byte result,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type,float min_value,float max_value,float increment) { - var msg = new mavlink_hwstatus_t(); + var msg = new mavlink_osd_param_show_config_reply_t(); - msg.Vcc = Vcc; - msg.I2Cerr = I2Cerr; + msg.request_id = request_id; + msg.result = result; + msg.param_id = param_id; + msg.config_type = config_type; + msg.min_value = min_value; + msg.max_value = max_value; + msg.increment = increment; return msg; } - /// Board voltage. [mV] - [Units("[mV]")] - [Description("Board voltage.")] + /// Request ID - copied from request. + [Units("")] + [Description("Request ID - copied from request.")] //[FieldOffset(0)] - public ushort Vcc; + public uint request_id; - /// I2C error count. + /// OSD parameter minimum value. [Units("")] - [Description("I2C error count.")] - //[FieldOffset(2)] - public byte I2Cerr; + [Description("OSD parameter minimum value.")] + //[FieldOffset(4)] + public float min_value; + + /// OSD parameter maximum value. + [Units("")] + [Description("OSD parameter maximum value.")] + //[FieldOffset(8)] + public float max_value; + + /// OSD parameter increment. + [Units("")] + [Description("OSD parameter increment.")] + //[FieldOffset(12)] + public float increment; + + /// Config error type. OSD_PARAM_CONFIG_ERROR + [Units("")] + [Description("Config error type.")] + //[FieldOffset(16)] + public /*OSD_PARAM_CONFIG_ERROR*/byte result; + + /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + [Units("")] + [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(17)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; + + /// Config type. OSD_PARAM_CONFIG_TYPE + [Units("")] + [Description("Config type.")] + //[FieldOffset(33)] + public /*OSD_PARAM_CONFIG_TYPE*/byte config_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Status generated by radio. - public struct mavlink_radio_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// Obstacle located as a 3D vector. + public struct mavlink_obstacle_distance_3d_t { /// packet ordered constructor - public mavlink_radio_t(ushort rxerrors,ushort @fixed,byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise) + public mavlink_obstacle_distance_3d_t(uint time_boot_ms,float x,float y,float z,float min_distance,float max_distance,ushort obstacle_id,/*MAV_DISTANCE_SENSOR*/byte sensor_type,/*MAV_FRAME*/byte frame) { - this.rxerrors = rxerrors; - this.@fixed = @fixed; - this.rssi = rssi; - this.remrssi = remrssi; - this.txbuf = txbuf; - this.noise = noise; - this.remnoise = remnoise; + this.time_boot_ms = time_boot_ms; + this.x = x; + this.y = y; + this.z = z; + this.min_distance = min_distance; + this.max_distance = max_distance; + this.obstacle_id = obstacle_id; + this.sensor_type = sensor_type; + this.frame = frame; } /// packet xml order - public static mavlink_radio_t PopulateXMLOrder(byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise,ushort rxerrors,ushort @fixed) + public static mavlink_obstacle_distance_3d_t PopulateXMLOrder(uint time_boot_ms,/*MAV_DISTANCE_SENSOR*/byte sensor_type,/*MAV_FRAME*/byte frame,ushort obstacle_id,float x,float y,float z,float min_distance,float max_distance) { - var msg = new mavlink_radio_t(); + var msg = new mavlink_obstacle_distance_3d_t(); - msg.rssi = rssi; - msg.remrssi = remrssi; - msg.txbuf = txbuf; - msg.noise = noise; - msg.remnoise = remnoise; - msg.rxerrors = rxerrors; - msg.@fixed = @fixed; + msg.time_boot_ms = time_boot_ms; + msg.sensor_type = sensor_type; + msg.frame = frame; + msg.obstacle_id = obstacle_id; + msg.x = x; + msg.y = y; + msg.z = z; + msg.min_distance = min_distance; + msg.max_distance = max_distance; return msg; } - /// Receive errors. - [Units("")] - [Description("Receive errors.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ushort rxerrors; - - /// Count of error corrected packets. - [Units("")] - [Description("Count of error corrected packets.")] - //[FieldOffset(2)] - public ushort @fixed; + public uint time_boot_ms; - /// Local signal strength. - [Units("")] - [Description("Local signal strength.")] + /// X position of the obstacle. [m] + [Units("[m]")] + [Description(" X position of the obstacle.")] //[FieldOffset(4)] - public byte rssi; + public float x; - /// Remote signal strength. - [Units("")] - [Description("Remote signal strength.")] - //[FieldOffset(5)] - public byte remrssi; + /// Y position of the obstacle. [m] + [Units("[m]")] + [Description(" Y position of the obstacle.")] + //[FieldOffset(8)] + public float y; - /// How full the tx buffer is. [%] - [Units("[%]")] - [Description("How full the tx buffer is.")] - //[FieldOffset(6)] - public byte txbuf; + /// Z position of the obstacle. [m] + [Units("[m]")] + [Description(" Z position of the obstacle.")] + //[FieldOffset(12)] + public float z; - /// Background noise level. + /// Minimum distance the sensor can measure. [m] + [Units("[m]")] + [Description("Minimum distance the sensor can measure.")] + //[FieldOffset(16)] + public float min_distance; + + /// Maximum distance the sensor can measure. [m] + [Units("[m]")] + [Description("Maximum distance the sensor can measure.")] + //[FieldOffset(20)] + public float max_distance; + + /// Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined. [Units("")] - [Description("Background noise level.")] - //[FieldOffset(7)] - public byte noise; + [Description(" Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.")] + //[FieldOffset(24)] + public ushort obstacle_id; - /// Remote background noise level. + /// Class id of the distance sensor type. MAV_DISTANCE_SENSOR [Units("")] - [Description("Remote background noise level.")] - //[FieldOffset(8)] - public byte remnoise; + [Description("Class id of the distance sensor type.")] + //[FieldOffset(26)] + public /*MAV_DISTANCE_SENSOR*/byte sensor_type; + + /// Coordinate frame of reference. MAV_FRAME + [Units("")] + [Description("Coordinate frame of reference.")] + //[FieldOffset(27)] + public /*MAV_FRAME*/byte frame; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - /// Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled. - public struct mavlink_limits_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] + /// Water depth + public struct mavlink_water_depth_t { /// packet ordered constructor - public mavlink_limits_status_t(uint last_trigger,uint last_action,uint last_recovery,uint last_clear,ushort breach_count,/*LIMITS_STATE*/byte limits_state,/*LIMIT_MODULE*/byte mods_enabled,/*LIMIT_MODULE*/byte mods_required,/*LIMIT_MODULE*/byte mods_triggered) + public mavlink_water_depth_t(uint time_boot_ms,int lat,int lng,float alt,float roll,float pitch,float yaw,float distance,float temperature,byte id,byte healthy) { - this.last_trigger = last_trigger; - this.last_action = last_action; - this.last_recovery = last_recovery; - this.last_clear = last_clear; - this.breach_count = breach_count; - this.limits_state = limits_state; - this.mods_enabled = mods_enabled; - this.mods_required = mods_required; - this.mods_triggered = mods_triggered; + this.time_boot_ms = time_boot_ms; + this.lat = lat; + this.lng = lng; + this.alt = alt; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.distance = distance; + this.temperature = temperature; + this.id = id; + this.healthy = healthy; } /// packet xml order - public static mavlink_limits_status_t PopulateXMLOrder(/*LIMITS_STATE*/byte limits_state,uint last_trigger,uint last_action,uint last_recovery,uint last_clear,ushort breach_count,/*LIMIT_MODULE*/byte mods_enabled,/*LIMIT_MODULE*/byte mods_required,/*LIMIT_MODULE*/byte mods_triggered) + public static mavlink_water_depth_t PopulateXMLOrder(uint time_boot_ms,byte id,byte healthy,int lat,int lng,float alt,float roll,float pitch,float yaw,float distance,float temperature) { - var msg = new mavlink_limits_status_t(); + var msg = new mavlink_water_depth_t(); - msg.limits_state = limits_state; - msg.last_trigger = last_trigger; - msg.last_action = last_action; - msg.last_recovery = last_recovery; - msg.last_clear = last_clear; - msg.breach_count = breach_count; - msg.mods_enabled = mods_enabled; - msg.mods_required = mods_required; - msg.mods_triggered = mods_triggered; + msg.time_boot_ms = time_boot_ms; + msg.id = id; + msg.healthy = healthy; + msg.lat = lat; + msg.lng = lng; + msg.alt = alt; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.distance = distance; + msg.temperature = temperature; return msg; } - /// Time (since boot) of last breach. [ms] + /// Timestamp (time since system boot) [ms] [Units("[ms]")] - [Description("Time (since boot) of last breach.")] + [Description("Timestamp (time since system boot)")] //[FieldOffset(0)] - public uint last_trigger; + public uint time_boot_ms; - /// Time (since boot) of last recovery action. [ms] - [Units("[ms]")] - [Description("Time (since boot) of last recovery action.")] + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] //[FieldOffset(4)] - public uint last_action; + public int lat; - /// Time (since boot) of last successful recovery. [ms] - [Units("[ms]")] - [Description("Time (since boot) of last successful recovery.")] + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] //[FieldOffset(8)] - public uint last_recovery; + public int lng; - /// Time (since boot) of last all-clear. [ms] - [Units("[ms]")] - [Description("Time (since boot) of last all-clear.")] + /// Altitude (MSL) of vehicle [m] + [Units("[m]")] + [Description("Altitude (MSL) of vehicle")] //[FieldOffset(12)] - public uint last_clear; + public float alt; - /// Number of fence breaches. - [Units("")] - [Description("Number of fence breaches.")] + /// Roll angle [rad] + [Units("[rad]")] + [Description("Roll angle")] //[FieldOffset(16)] - public ushort breach_count; + public float roll; - /// State of AP_Limits. LIMITS_STATE - [Units("")] - [Description("State of AP_Limits.")] - //[FieldOffset(18)] - public /*LIMITS_STATE*/byte limits_state; + /// Pitch angle [rad] + [Units("[rad]")] + [Description("Pitch angle")] + //[FieldOffset(20)] + public float pitch; - /// AP_Limit_Module bitfield of enabled modules. LIMIT_MODULE bitmask - [Units("")] - [Description("AP_Limit_Module bitfield of enabled modules.")] - //[FieldOffset(19)] - public /*LIMIT_MODULE*/byte mods_enabled; + /// Yaw angle [rad] + [Units("[rad]")] + [Description("Yaw angle")] + //[FieldOffset(24)] + public float yaw; - /// AP_Limit_Module bitfield of required modules. LIMIT_MODULE bitmask + /// Distance (uncorrected) [m] + [Units("[m]")] + [Description("Distance (uncorrected)")] + //[FieldOffset(28)] + public float distance; + + /// Water temperature [degC] + [Units("[degC]")] + [Description("Water temperature")] + //[FieldOffset(32)] + public float temperature; + + /// Onboard ID of the sensor [Units("")] - [Description("AP_Limit_Module bitfield of required modules.")] - //[FieldOffset(20)] - public /*LIMIT_MODULE*/byte mods_required; + [Description("Onboard ID of the sensor")] + //[FieldOffset(36)] + public byte id; - /// AP_Limit_Module bitfield of triggered modules. LIMIT_MODULE bitmask + /// Sensor data healthy (0=unhealthy, 1=healthy) [Units("")] - [Description("AP_Limit_Module bitfield of triggered modules.")] - //[FieldOffset(21)] - public /*LIMIT_MODULE*/byte mods_triggered; + [Description("Sensor data healthy (0=unhealthy, 1=healthy)")] + //[FieldOffset(37)] + public byte healthy; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - /// Wind estimation. - public struct mavlink_wind_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// The MCU status, giving MCU temperature and voltage. The min and max voltages are to allow for detecting power supply instability. + public struct mavlink_mcu_status_t { /// packet ordered constructor - public mavlink_wind_t(float direction,float speed,float speed_z) + public mavlink_mcu_status_t(short MCU_temperature,ushort MCU_voltage,ushort MCU_voltage_min,ushort MCU_voltage_max,byte id) { - this.direction = direction; - this.speed = speed; - this.speed_z = speed_z; + this.MCU_temperature = MCU_temperature; + this.MCU_voltage = MCU_voltage; + this.MCU_voltage_min = MCU_voltage_min; + this.MCU_voltage_max = MCU_voltage_max; + this.id = id; } /// packet xml order - public static mavlink_wind_t PopulateXMLOrder(float direction,float speed,float speed_z) + public static mavlink_mcu_status_t PopulateXMLOrder(byte id,short MCU_temperature,ushort MCU_voltage,ushort MCU_voltage_min,ushort MCU_voltage_max) { - var msg = new mavlink_wind_t(); + var msg = new mavlink_mcu_status_t(); - msg.direction = direction; - msg.speed = speed; - msg.speed_z = speed_z; + msg.id = id; + msg.MCU_temperature = MCU_temperature; + msg.MCU_voltage = MCU_voltage; + msg.MCU_voltage_min = MCU_voltage_min; + msg.MCU_voltage_max = MCU_voltage_max; return msg; } - /// Wind direction (that wind is coming from). [deg] - [Units("[deg]")] - [Description("Wind direction (that wind is coming from).")] + /// MCU Internal temperature [cdegC] + [Units("[cdegC]")] + [Description("MCU Internal temperature")] //[FieldOffset(0)] - public float direction; + public short MCU_temperature; - /// Wind speed in ground plane. [m/s] - [Units("[m/s]")] - [Description("Wind speed in ground plane.")] + /// MCU voltage [mV] + [Units("[mV]")] + [Description("MCU voltage")] + //[FieldOffset(2)] + public ushort MCU_voltage; + + /// MCU voltage minimum [mV] + [Units("[mV]")] + [Description("MCU voltage minimum")] //[FieldOffset(4)] - public float speed; + public ushort MCU_voltage_min; - /// Vertical wind speed. [m/s] - [Units("[m/s]")] - [Description("Vertical wind speed.")] + /// MCU voltage maximum [mV] + [Units("[mV]")] + [Description("MCU voltage maximum")] + //[FieldOffset(6)] + public ushort MCU_voltage_max; + + /// MCU instance + [Units("")] + [Description("MCU instance")] //[FieldOffset(8)] - public float speed_z; + public byte id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - /// Data packet, size 16. - public struct mavlink_data16_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 13 to 16, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_13_to_16_t { /// packet ordered constructor - public mavlink_data16_t(byte type,byte len,byte[] data) + public mavlink_esc_telemetry_13_to_16_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.type = type; - this.len = len; - this.data = data; + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_data16_t PopulateXMLOrder(byte type,byte len,byte[] data) + public static mavlink_esc_telemetry_13_to_16_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_data16_t(); + var msg = new mavlink_esc_telemetry_13_to_16_t(); - msg.type = type; - msg.len = len; - msg.data = data; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; return msg; } - /// Data type. - [Units("")] - [Description("Data type.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public byte type; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; - /// Data length. [bytes] - [Units("[bytes]")] - [Description("Data length.")] - //[FieldOffset(1)] - public byte len; + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; - /// Raw data. + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; + + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; + + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("Raw data.")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] data; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] - /// Data packet, size 32. - public struct mavlink_data32_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 17 to 20, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_17_to_20_t { /// packet ordered constructor - public mavlink_data32_t(byte type,byte len,byte[] data) + public mavlink_esc_telemetry_17_to_20_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.type = type; - this.len = len; - this.data = data; + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_data32_t PopulateXMLOrder(byte type,byte len,byte[] data) + public static mavlink_esc_telemetry_17_to_20_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_data32_t(); + var msg = new mavlink_esc_telemetry_17_to_20_t(); - msg.type = type; - msg.len = len; - msg.data = data; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; return msg; } - /// Data type. - [Units("")] - [Description("Data type.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public byte type; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; + + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; - /// Data length. [bytes] - [Units("[bytes]")] - [Description("Data length.")] - //[FieldOffset(1)] - public byte len; + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; - /// Raw data. + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; + + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("Raw data.")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] data; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=66)] - /// Data packet, size 64. - public struct mavlink_data64_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 21 to 24, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_21_to_24_t { /// packet ordered constructor - public mavlink_data64_t(byte type,byte len,byte[] data) + public mavlink_esc_telemetry_21_to_24_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.type = type; - this.len = len; - this.data = data; + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_data64_t PopulateXMLOrder(byte type,byte len,byte[] data) + public static mavlink_esc_telemetry_21_to_24_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_data64_t(); + var msg = new mavlink_esc_telemetry_21_to_24_t(); - msg.type = type; - msg.len = len; - msg.data = data; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; return msg; } - /// Data type. - [Units("")] - [Description("Data type.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public byte type; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; - /// Data length. [bytes] - [Units("[bytes]")] - [Description("Data length.")] - //[FieldOffset(1)] - public byte len; + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; - /// Raw data. + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; + + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; + + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("Raw data.")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=64)] - public byte[] data; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=98)] - /// Data packet, size 96. - public struct mavlink_data96_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 25 to 28, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_25_to_28_t { /// packet ordered constructor - public mavlink_data96_t(byte type,byte len,byte[] data) + public mavlink_esc_telemetry_25_to_28_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.type = type; - this.len = len; - this.data = data; + this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_data96_t PopulateXMLOrder(byte type,byte len,byte[] data) + public static mavlink_esc_telemetry_25_to_28_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_data96_t(); + var msg = new mavlink_esc_telemetry_25_to_28_t(); - msg.type = type; - msg.len = len; - msg.data = data; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; return msg; } - /// Data type. - [Units("")] - [Description("Data type.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public byte type; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; - /// Data length. [bytes] - [Units("[bytes]")] - [Description("Data length.")] - //[FieldOffset(1)] - public byte len; + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; - /// Raw data. + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; + + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; + + /// count of telemetry packets received (wraps at 65535). [Units("")] - [Description("Raw data.")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=96)] - public byte[] data; + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// Rangefinder reporting. - public struct mavlink_rangefinder_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// ESC Telemetry Data for ESCs 29 to 32, matching data sent by BLHeli ESCs. + public struct mavlink_esc_telemetry_29_to_32_t { /// packet ordered constructor - public mavlink_rangefinder_t(float distance,float voltage) + public mavlink_esc_telemetry_29_to_32_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) { - this.distance = distance; this.voltage = voltage; + this.current = current; + this.totalcurrent = totalcurrent; + this.rpm = rpm; + this.count = count; + this.temperature = temperature; } /// packet xml order - public static mavlink_rangefinder_t PopulateXMLOrder(float distance,float voltage) + public static mavlink_esc_telemetry_29_to_32_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) { - var msg = new mavlink_rangefinder_t(); + var msg = new mavlink_esc_telemetry_29_to_32_t(); - msg.distance = distance; + msg.temperature = temperature; msg.voltage = voltage; + msg.current = current; + msg.totalcurrent = totalcurrent; + msg.rpm = rpm; + msg.count = count; return msg; } - /// Distance. [m] - [Units("[m]")] - [Description("Distance.")] + /// Voltage. [cV] + [Units("[cV]")] + [Description("Voltage.")] //[FieldOffset(0)] - public float distance; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltage; - /// Raw voltage if available, zero otherwise. [V] - [Units("[V]")] - [Description("Raw voltage if available, zero otherwise.")] - //[FieldOffset(4)] - public float voltage; + /// Current. [cA] + [Units("[cA]")] + [Description("Current.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] current; + + /// Total current. [mAh] + [Units("[mAh]")] + [Description("Total current.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] totalcurrent; + + /// RPM (eRPM). [rpm] + [Units("[rpm]")] + [Description("RPM (eRPM).")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] rpm; + + /// count of telemetry packets received (wraps at 65535). + [Units("")] + [Description("count of telemetry packets received (wraps at 65535).")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] count; + + /// Temperature. [degC] + [Units("[degC]")] + [Description("Temperature.")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=48)] - /// Airspeed auto-calibration. - public struct mavlink_airspeed_autocal_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=47)] + /// Message encoding a command with parameters as scaled integers and additional metadata. Scaling depends on the actual command value. + public struct mavlink_command_int_stamped_t { /// packet ordered constructor - public mavlink_airspeed_autocal_t(float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz) + public mavlink_command_int_stamped_t(ulong vehicle_timestamp,uint utc_time,float param1,float param2,float param3,float param4,int x,int y,float z,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue) { - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.diff_pressure = diff_pressure; - this.EAS2TAS = EAS2TAS; - this.ratio = ratio; - this.state_x = state_x; - this.state_y = state_y; - this.state_z = state_z; - this.Pax = Pax; - this.Pby = Pby; - this.Pcz = Pcz; + this.vehicle_timestamp = vehicle_timestamp; + this.utc_time = utc_time; + this.param1 = param1; + this.param2 = param2; + this.param3 = param3; + this.param4 = param4; + this.x = x; + this.y = y; + this.z = z; + this.command = command; + this.target_system = target_system; + this.target_component = target_component; + this.frame = frame; + this.current = current; + this.autocontinue = autocontinue; } /// packet xml order - public static mavlink_airspeed_autocal_t PopulateXMLOrder(float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz) + public static mavlink_command_int_stamped_t PopulateXMLOrder(uint utc_time,ulong vehicle_timestamp,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,int x,int y,float z) { - var msg = new mavlink_airspeed_autocal_t(); + var msg = new mavlink_command_int_stamped_t(); - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.diff_pressure = diff_pressure; - msg.EAS2TAS = EAS2TAS; - msg.ratio = ratio; - msg.state_x = state_x; - msg.state_y = state_y; - msg.state_z = state_z; - msg.Pax = Pax; - msg.Pby = Pby; - msg.Pcz = Pcz; + msg.utc_time = utc_time; + msg.vehicle_timestamp = vehicle_timestamp; + msg.target_system = target_system; + msg.target_component = target_component; + msg.frame = frame; + msg.command = command; + msg.current = current; + msg.autocontinue = autocontinue; + msg.param1 = param1; + msg.param2 = param2; + msg.param3 = param3; + msg.param4 = param4; + msg.x = x; + msg.y = y; + msg.z = z; return msg; } - /// GPS velocity north. [m/s] - [Units("[m/s]")] - [Description("GPS velocity north.")] + /// Microseconds elapsed since vehicle boot + [Units("")] + [Description("Microseconds elapsed since vehicle boot")] //[FieldOffset(0)] - public float vx; - - /// GPS velocity east. [m/s] - [Units("[m/s]")] - [Description("GPS velocity east.")] - //[FieldOffset(4)] - public float vy; + public ulong vehicle_timestamp; - /// GPS velocity down. [m/s] - [Units("[m/s]")] - [Description("GPS velocity down.")] + /// UTC time, seconds elapsed since 01.01.1970 + [Units("")] + [Description("UTC time, seconds elapsed since 01.01.1970")] //[FieldOffset(8)] - public float vz; + public uint utc_time; - /// Differential pressure. [Pa] - [Units("[Pa]")] - [Description("Differential pressure.")] + /// PARAM1, see MAV_CMD enum + [Units("")] + [Description("PARAM1, see MAV_CMD enum")] //[FieldOffset(12)] - public float diff_pressure; + public float param1; - /// Estimated to true airspeed ratio. + /// PARAM2, see MAV_CMD enum [Units("")] - [Description("Estimated to true airspeed ratio.")] + [Description("PARAM2, see MAV_CMD enum")] //[FieldOffset(16)] - public float EAS2TAS; + public float param2; - /// Airspeed ratio. + /// PARAM3, see MAV_CMD enum [Units("")] - [Description("Airspeed ratio.")] + [Description("PARAM3, see MAV_CMD enum")] //[FieldOffset(20)] - public float ratio; + public float param3; - /// EKF state x. + /// PARAM4, see MAV_CMD enum [Units("")] - [Description("EKF state x.")] + [Description("PARAM4, see MAV_CMD enum")] //[FieldOffset(24)] - public float state_x; + public float param4; - /// EKF state y. + /// PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 [Units("")] - [Description("EKF state y.")] + [Description("PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7")] //[FieldOffset(28)] - public float state_y; + public int x; - /// EKF state z. + /// PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 [Units("")] - [Description("EKF state z.")] + [Description("PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7")] //[FieldOffset(32)] - public float state_z; + public int y; - /// EKF Pax. + /// PARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame). [Units("")] - [Description("EKF Pax.")] + [Description("PARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame).")] //[FieldOffset(36)] - public float Pax; + public float z; - /// EKF Pby. + /// The scheduled action for the mission item, as defined by MAV_CMD enum MAV_CMD [Units("")] - [Description("EKF Pby.")] + [Description("The scheduled action for the mission item, as defined by MAV_CMD enum")] //[FieldOffset(40)] - public float Pby; + public /*MAV_CMD*/ushort command; - /// EKF Pcz. + /// System ID [Units("")] - [Description("EKF Pcz.")] + [Description("System ID")] + //[FieldOffset(42)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(43)] + public byte target_component; + + /// The coordinate system of the COMMAND, as defined by MAV_FRAME enum MAV_FRAME + [Units("")] + [Description("The coordinate system of the COMMAND, as defined by MAV_FRAME enum")] //[FieldOffset(44)] - public float Pcz; + public /*MAV_FRAME*/byte frame; + + /// false:0, true:1 + [Units("")] + [Description("false:0, true:1")] + //[FieldOffset(45)] + public byte current; + + /// autocontinue to next wp + [Units("")] + [Description("autocontinue to next wp")] + //[FieldOffset(46)] + public byte autocontinue; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] - /// A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS. - public struct mavlink_rally_point_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=45)] + /// Send a command with up to seven parameters to the MAV and additional metadata + public struct mavlink_command_long_stamped_t { /// packet ordered constructor - public mavlink_rally_point_t(int lat,int lng,short alt,short break_alt,ushort land_dir,byte target_system,byte target_component,byte idx,byte count,/*RALLY_FLAGS*/byte flags) + public mavlink_command_long_stamped_t(ulong vehicle_timestamp,uint utc_time,float param1,float param2,float param3,float param4,float param5,float param6,float param7,/*MAV_CMD*/ushort command,byte target_system,byte target_component,byte confirmation) { - this.lat = lat; - this.lng = lng; - this.alt = alt; - this.break_alt = break_alt; - this.land_dir = land_dir; + this.vehicle_timestamp = vehicle_timestamp; + this.utc_time = utc_time; + this.param1 = param1; + this.param2 = param2; + this.param3 = param3; + this.param4 = param4; + this.param5 = param5; + this.param6 = param6; + this.param7 = param7; + this.command = command; this.target_system = target_system; this.target_component = target_component; - this.idx = idx; - this.count = count; - this.flags = flags; + this.confirmation = confirmation; } /// packet xml order - public static mavlink_rally_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx,byte count,int lat,int lng,short alt,short break_alt,ushort land_dir,/*RALLY_FLAGS*/byte flags) + public static mavlink_command_long_stamped_t PopulateXMLOrder(uint utc_time,ulong vehicle_timestamp,byte target_system,byte target_component,/*MAV_CMD*/ushort command,byte confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) { - var msg = new mavlink_rally_point_t(); + var msg = new mavlink_command_long_stamped_t(); + msg.utc_time = utc_time; + msg.vehicle_timestamp = vehicle_timestamp; msg.target_system = target_system; msg.target_component = target_component; - msg.idx = idx; - msg.count = count; - msg.lat = lat; - msg.lng = lng; - msg.alt = alt; - msg.break_alt = break_alt; - msg.land_dir = land_dir; - msg.flags = flags; + msg.command = command; + msg.confirmation = confirmation; + msg.param1 = param1; + msg.param2 = param2; + msg.param3 = param3; + msg.param4 = param4; + msg.param5 = param5; + msg.param6 = param6; + msg.param7 = param7; return msg; } - /// Latitude of point. [degE7] - [Units("[degE7]")] - [Description("Latitude of point.")] + /// Microseconds elapsed since vehicle boot + [Units("")] + [Description("Microseconds elapsed since vehicle boot")] //[FieldOffset(0)] - public int lat; - - /// Longitude of point. [degE7] - [Units("[degE7]")] - [Description("Longitude of point.")] - //[FieldOffset(4)] - public int lng; + public ulong vehicle_timestamp; - /// Transit / loiter altitude relative to home. [m] - [Units("[m]")] - [Description("Transit / loiter altitude relative to home.")] + /// UTC time, seconds elapsed since 01.01.1970 + [Units("")] + [Description("UTC time, seconds elapsed since 01.01.1970")] //[FieldOffset(8)] - public short alt; - - /// Break altitude relative to home. [m] - [Units("[m]")] - [Description("Break altitude relative to home.")] - //[FieldOffset(10)] - public short break_alt; + public uint utc_time; - /// Heading to aim for when landing. [cdeg] - [Units("[cdeg]")] - [Description("Heading to aim for when landing.")] + /// Parameter 1, as defined by MAV_CMD enum. + [Units("")] + [Description("Parameter 1, as defined by MAV_CMD enum.")] //[FieldOffset(12)] - public ushort land_dir; + public float param1; - /// System ID. + /// Parameter 2, as defined by MAV_CMD enum. [Units("")] - [Description("System ID.")] - //[FieldOffset(14)] - public byte target_system; + [Description("Parameter 2, as defined by MAV_CMD enum.")] + //[FieldOffset(16)] + public float param2; - /// Component ID. + /// Parameter 3, as defined by MAV_CMD enum. [Units("")] - [Description("Component ID.")] - //[FieldOffset(15)] - public byte target_component; + [Description("Parameter 3, as defined by MAV_CMD enum.")] + //[FieldOffset(20)] + public float param3; - /// Point index (first point is 0). + /// Parameter 4, as defined by MAV_CMD enum. [Units("")] - [Description("Point index (first point is 0).")] - //[FieldOffset(16)] - public byte idx; + [Description("Parameter 4, as defined by MAV_CMD enum.")] + //[FieldOffset(24)] + public float param4; - /// Total number of points (for sanity checking). + /// Parameter 5, as defined by MAV_CMD enum. [Units("")] - [Description("Total number of points (for sanity checking).")] - //[FieldOffset(17)] - public byte count; + [Description("Parameter 5, as defined by MAV_CMD enum.")] + //[FieldOffset(28)] + public float param5; - /// Configuration flags. RALLY_FLAGS bitmask + /// Parameter 6, as defined by MAV_CMD enum. [Units("")] - [Description("Configuration flags.")] - //[FieldOffset(18)] - public /*RALLY_FLAGS*/byte flags; - }; + [Description("Parameter 6, as defined by MAV_CMD enum.")] + //[FieldOffset(32)] + public float param6; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. - public struct mavlink_rally_fetch_point_t - { - /// packet ordered constructor - public mavlink_rally_fetch_point_t(byte target_system,byte target_component,byte idx) - { - this.target_system = target_system; - this.target_component = target_component; - this.idx = idx; - - } - - /// packet xml order - public static mavlink_rally_fetch_point_t PopulateXMLOrder(byte target_system,byte target_component,byte idx) - { - var msg = new mavlink_rally_fetch_point_t(); + /// Parameter 7, as defined by MAV_CMD enum. + [Units("")] + [Description("Parameter 7, as defined by MAV_CMD enum.")] + //[FieldOffset(36)] + public float param7; - msg.target_system = target_system; - msg.target_component = target_component; - msg.idx = idx; - - return msg; - } - + /// Command ID, as defined by MAV_CMD enum. MAV_CMD + [Units("")] + [Description("Command ID, as defined by MAV_CMD enum.")] + //[FieldOffset(40)] + public /*MAV_CMD*/ushort command; - /// System ID. + /// System which should execute the command [Units("")] - [Description("System ID.")] - //[FieldOffset(0)] + [Description("System which should execute the command")] + //[FieldOffset(42)] public byte target_system; - /// Component ID. + /// Component which should execute the command, 0 for all components [Units("")] - [Description("Component ID.")] - //[FieldOffset(1)] + [Description("Component which should execute the command, 0 for all components")] + //[FieldOffset(43)] public byte target_component; - /// Point index (first point is 0). + /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) [Units("")] - [Description("Point index (first point is 0).")] - //[FieldOffset(2)] - public byte idx; + [Description("0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)")] + //[FieldOffset(44)] + public byte confirmation; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Status of compassmot calibration. - public struct mavlink_compassmot_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Voltage and current sensor data + public struct mavlink_sens_power_t { /// packet ordered constructor - public mavlink_compassmot_status_t(float current,float CompensationX,float CompensationY,float CompensationZ,ushort throttle,ushort interference) + public mavlink_sens_power_t(float adc121_vspb_volt,float adc121_cspb_amp,float adc121_cs1_amp,float adc121_cs2_amp) { - this.current = current; - this.CompensationX = CompensationX; - this.CompensationY = CompensationY; - this.CompensationZ = CompensationZ; - this.throttle = throttle; - this.interference = interference; + this.adc121_vspb_volt = adc121_vspb_volt; + this.adc121_cspb_amp = adc121_cspb_amp; + this.adc121_cs1_amp = adc121_cs1_amp; + this.adc121_cs2_amp = adc121_cs2_amp; } /// packet xml order - public static mavlink_compassmot_status_t PopulateXMLOrder(ushort throttle,float current,ushort interference,float CompensationX,float CompensationY,float CompensationZ) + public static mavlink_sens_power_t PopulateXMLOrder(float adc121_vspb_volt,float adc121_cspb_amp,float adc121_cs1_amp,float adc121_cs2_amp) { - var msg = new mavlink_compassmot_status_t(); + var msg = new mavlink_sens_power_t(); - msg.throttle = throttle; - msg.current = current; - msg.interference = interference; - msg.CompensationX = CompensationX; - msg.CompensationY = CompensationY; - msg.CompensationZ = CompensationZ; + msg.adc121_vspb_volt = adc121_vspb_volt; + msg.adc121_cspb_amp = adc121_cspb_amp; + msg.adc121_cs1_amp = adc121_cs1_amp; + msg.adc121_cs2_amp = adc121_cs2_amp; return msg; } - /// Current. [A] - [Units("[A]")] - [Description("Current.")] + /// Power board voltage sensor reading [V] + [Units("[V]")] + [Description(" Power board voltage sensor reading")] //[FieldOffset(0)] - public float current; + public float adc121_vspb_volt; - /// Motor Compensation X. - [Units("")] - [Description("Motor Compensation X.")] + /// Power board current sensor reading [A] + [Units("[A]")] + [Description(" Power board current sensor reading")] //[FieldOffset(4)] - public float CompensationX; + public float adc121_cspb_amp; - /// Motor Compensation Y. - [Units("")] - [Description("Motor Compensation Y.")] + /// Board current sensor 1 reading [A] + [Units("[A]")] + [Description(" Board current sensor 1 reading")] //[FieldOffset(8)] - public float CompensationY; + public float adc121_cs1_amp; - /// Motor Compensation Z. - [Units("")] - [Description("Motor Compensation Z.")] + /// Board current sensor 2 reading [A] + [Units("[A]")] + [Description(" Board current sensor 2 reading")] //[FieldOffset(12)] - public float CompensationZ; - - /// Throttle. [d%] - [Units("[d%]")] - [Description("Throttle.")] - //[FieldOffset(16)] - public ushort throttle; - - /// Interference. [%] - [Units("[%]")] - [Description("Interference.")] - //[FieldOffset(18)] - public ushort interference; + public float adc121_cs2_amp; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] - /// Status of secondary AHRS filter if available. - public struct mavlink_ahrs2_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=41)] + /// Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking + public struct mavlink_sens_mppt_t { /// packet ordered constructor - public mavlink_ahrs2_t(float roll,float pitch,float yaw,float altitude,int lat,int lng) + public mavlink_sens_mppt_t(ulong mppt_timestamp,float mppt1_volt,float mppt1_amp,float mppt2_volt,float mppt2_amp,float mppt3_volt,float mppt3_amp,ushort mppt1_pwm,ushort mppt2_pwm,ushort mppt3_pwm,byte mppt1_status,byte mppt2_status,byte mppt3_status) { - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.altitude = altitude; - this.lat = lat; - this.lng = lng; + this.mppt_timestamp = mppt_timestamp; + this.mppt1_volt = mppt1_volt; + this.mppt1_amp = mppt1_amp; + this.mppt2_volt = mppt2_volt; + this.mppt2_amp = mppt2_amp; + this.mppt3_volt = mppt3_volt; + this.mppt3_amp = mppt3_amp; + this.mppt1_pwm = mppt1_pwm; + this.mppt2_pwm = mppt2_pwm; + this.mppt3_pwm = mppt3_pwm; + this.mppt1_status = mppt1_status; + this.mppt2_status = mppt2_status; + this.mppt3_status = mppt3_status; } /// packet xml order - public static mavlink_ahrs2_t PopulateXMLOrder(float roll,float pitch,float yaw,float altitude,int lat,int lng) + public static mavlink_sens_mppt_t PopulateXMLOrder(ulong mppt_timestamp,float mppt1_volt,float mppt1_amp,ushort mppt1_pwm,byte mppt1_status,float mppt2_volt,float mppt2_amp,ushort mppt2_pwm,byte mppt2_status,float mppt3_volt,float mppt3_amp,ushort mppt3_pwm,byte mppt3_status) { - var msg = new mavlink_ahrs2_t(); + var msg = new mavlink_sens_mppt_t(); - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.altitude = altitude; - msg.lat = lat; - msg.lng = lng; + msg.mppt_timestamp = mppt_timestamp; + msg.mppt1_volt = mppt1_volt; + msg.mppt1_amp = mppt1_amp; + msg.mppt1_pwm = mppt1_pwm; + msg.mppt1_status = mppt1_status; + msg.mppt2_volt = mppt2_volt; + msg.mppt2_amp = mppt2_amp; + msg.mppt2_pwm = mppt2_pwm; + msg.mppt2_status = mppt2_status; + msg.mppt3_volt = mppt3_volt; + msg.mppt3_amp = mppt3_amp; + msg.mppt3_pwm = mppt3_pwm; + msg.mppt3_status = mppt3_status; return msg; } - /// Roll angle. [rad] - [Units("[rad]")] - [Description("Roll angle.")] + /// MPPT last timestamp [us] + [Units("[us]")] + [Description(" MPPT last timestamp ")] //[FieldOffset(0)] - public float roll; - - /// Pitch angle. [rad] - [Units("[rad]")] - [Description("Pitch angle.")] - //[FieldOffset(4)] - public float pitch; + public ulong mppt_timestamp; - /// Yaw angle. [rad] - [Units("[rad]")] - [Description("Yaw angle.")] + /// MPPT1 voltage [V] + [Units("[V]")] + [Description(" MPPT1 voltage ")] //[FieldOffset(8)] - public float yaw; + public float mppt1_volt; - /// Altitude (MSL). [m] - [Units("[m]")] - [Description("Altitude (MSL).")] + /// MPPT1 current [A] + [Units("[A]")] + [Description(" MPPT1 current ")] //[FieldOffset(12)] - public float altitude; + public float mppt1_amp; - /// Latitude. [degE7] - [Units("[degE7]")] - [Description("Latitude.")] + /// MPPT2 voltage [V] + [Units("[V]")] + [Description(" MPPT2 voltage ")] //[FieldOffset(16)] - public int lat; + public float mppt2_volt; - /// Longitude. [degE7] - [Units("[degE7]")] - [Description("Longitude.")] + /// MPPT2 current [A] + [Units("[A]")] + [Description(" MPPT2 current ")] //[FieldOffset(20)] - public int lng; + public float mppt2_amp; + + /// MPPT3 voltage [V] + [Units("[V]")] + [Description("MPPT3 voltage ")] + //[FieldOffset(24)] + public float mppt3_volt; + + /// MPPT3 current [A] + [Units("[A]")] + [Description(" MPPT3 current ")] + //[FieldOffset(28)] + public float mppt3_amp; + + /// MPPT1 pwm [us] + [Units("[us]")] + [Description(" MPPT1 pwm ")] + //[FieldOffset(32)] + public ushort mppt1_pwm; + + /// MPPT2 pwm [us] + [Units("[us]")] + [Description(" MPPT2 pwm ")] + //[FieldOffset(34)] + public ushort mppt2_pwm; + + /// MPPT3 pwm [us] + [Units("[us]")] + [Description(" MPPT3 pwm ")] + //[FieldOffset(36)] + public ushort mppt3_pwm; + + /// MPPT1 status + [Units("")] + [Description(" MPPT1 status ")] + //[FieldOffset(38)] + public byte mppt1_status; + + /// MPPT2 status + [Units("")] + [Description(" MPPT2 status ")] + //[FieldOffset(39)] + public byte mppt2_status; + + /// MPPT3 status + [Units("")] + [Description(" MPPT3 status ")] + //[FieldOffset(40)] + public byte mppt3_status; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=29)] - /// Camera Event. - public struct mavlink_camera_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=98)] + /// ASL-fixed-wing controller data + public struct mavlink_aslctrl_data_t { /// packet ordered constructor - public mavlink_camera_status_t(ulong time_usec,float p1,float p2,float p3,float p4,ushort img_idx,byte target_system,byte cam_idx,/*CAMERA_STATUS_TYPES*/byte event_id) + public mavlink_aslctrl_data_t(ulong timestamp,float h,float hRef,float hRef_t,float PitchAngle,float PitchAngleRef,float q,float qRef,float uElev,float uThrot,float uThrot2,float nZ,float AirspeedRef,float YawAngle,float YawAngleRef,float RollAngle,float RollAngleRef,float p,float pRef,float r,float rRef,float uAil,float uRud,byte aslctrl_mode,byte SpoilersEngaged) { - this.time_usec = time_usec; - this.p1 = p1; - this.p2 = p2; - this.p3 = p3; - this.p4 = p4; - this.img_idx = img_idx; - this.target_system = target_system; - this.cam_idx = cam_idx; - this.event_id = event_id; + this.timestamp = timestamp; + this.h = h; + this.hRef = hRef; + this.hRef_t = hRef_t; + this.PitchAngle = PitchAngle; + this.PitchAngleRef = PitchAngleRef; + this.q = q; + this.qRef = qRef; + this.uElev = uElev; + this.uThrot = uThrot; + this.uThrot2 = uThrot2; + this.nZ = nZ; + this.AirspeedRef = AirspeedRef; + this.YawAngle = YawAngle; + this.YawAngleRef = YawAngleRef; + this.RollAngle = RollAngle; + this.RollAngleRef = RollAngleRef; + this.p = p; + this.pRef = pRef; + this.r = r; + this.rRef = rRef; + this.uAil = uAil; + this.uRud = uRud; + this.aslctrl_mode = aslctrl_mode; + this.SpoilersEngaged = SpoilersEngaged; } /// packet xml order - public static mavlink_camera_status_t PopulateXMLOrder(ulong time_usec,byte target_system,byte cam_idx,ushort img_idx,/*CAMERA_STATUS_TYPES*/byte event_id,float p1,float p2,float p3,float p4) + public static mavlink_aslctrl_data_t PopulateXMLOrder(ulong timestamp,byte aslctrl_mode,float h,float hRef,float hRef_t,float PitchAngle,float PitchAngleRef,float q,float qRef,float uElev,float uThrot,float uThrot2,float nZ,float AirspeedRef,byte SpoilersEngaged,float YawAngle,float YawAngleRef,float RollAngle,float RollAngleRef,float p,float pRef,float r,float rRef,float uAil,float uRud) { - var msg = new mavlink_camera_status_t(); + var msg = new mavlink_aslctrl_data_t(); - msg.time_usec = time_usec; - msg.target_system = target_system; - msg.cam_idx = cam_idx; - msg.img_idx = img_idx; - msg.event_id = event_id; - msg.p1 = p1; - msg.p2 = p2; - msg.p3 = p3; - msg.p4 = p4; + msg.timestamp = timestamp; + msg.aslctrl_mode = aslctrl_mode; + msg.h = h; + msg.hRef = hRef; + msg.hRef_t = hRef_t; + msg.PitchAngle = PitchAngle; + msg.PitchAngleRef = PitchAngleRef; + msg.q = q; + msg.qRef = qRef; + msg.uElev = uElev; + msg.uThrot = uThrot; + msg.uThrot2 = uThrot2; + msg.nZ = nZ; + msg.AirspeedRef = AirspeedRef; + msg.SpoilersEngaged = SpoilersEngaged; + msg.YawAngle = YawAngle; + msg.YawAngleRef = YawAngleRef; + msg.RollAngle = RollAngle; + msg.RollAngleRef = RollAngleRef; + msg.p = p; + msg.pRef = pRef; + msg.r = r; + msg.rRef = rRef; + msg.uAil = uAil; + msg.uRud = uRud; return msg; } - /// Image timestamp (since UNIX epoch, according to camera clock). [us] + /// Timestamp [us] [Units("[us]")] - [Description("Image timestamp (since UNIX epoch, according to camera clock).")] + [Description(" Timestamp")] //[FieldOffset(0)] - public ulong time_usec; + public ulong timestamp; - /// Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + /// See sourcecode for a description of these values... [Units("")] - [Description("Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + [Description(" See sourcecode for a description of these values... ")] //[FieldOffset(8)] - public float p1; + public float h; - /// Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + /// [Units("")] - [Description("Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + [Description(" ")] //[FieldOffset(12)] - public float p2; + public float hRef; - /// Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). + /// [Units("")] - [Description("Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + [Description(" ")] //[FieldOffset(16)] - public float p3; + public float hRef_t; - /// Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). - [Units("")] - [Description("Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).")] + /// Pitch angle [deg] + [Units("[deg]")] + [Description("Pitch angle")] //[FieldOffset(20)] - public float p4; + public float PitchAngle; - /// Image index. - [Units("")] - [Description("Image index.")] + /// Pitch angle reference [deg] + [Units("[deg]")] + [Description("Pitch angle reference")] //[FieldOffset(24)] - public ushort img_idx; + public float PitchAngleRef; - /// System ID. + /// [Units("")] - [Description("System ID.")] - //[FieldOffset(26)] - public byte target_system; + [Description(" ")] + //[FieldOffset(28)] + public float q; - /// Camera ID. + /// [Units("")] - [Description("Camera ID.")] - //[FieldOffset(27)] - public byte cam_idx; + [Description(" ")] + //[FieldOffset(32)] + public float qRef; - /// Event type. CAMERA_STATUS_TYPES + /// [Units("")] - [Description("Event type.")] - //[FieldOffset(28)] - public /*CAMERA_STATUS_TYPES*/byte event_id; + [Description(" ")] + //[FieldOffset(36)] + public float uElev; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(40)] + public float uThrot; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(44)] + public float uThrot2; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(48)] + public float nZ; + + /// Airspeed reference [m/s] + [Units("[m/s]")] + [Description("Airspeed reference")] + //[FieldOffset(52)] + public float AirspeedRef; + + /// Yaw angle [deg] + [Units("[deg]")] + [Description("Yaw angle")] + //[FieldOffset(56)] + public float YawAngle; + + /// Yaw angle reference [deg] + [Units("[deg]")] + [Description("Yaw angle reference")] + //[FieldOffset(60)] + public float YawAngleRef; + + /// Roll angle [deg] + [Units("[deg]")] + [Description("Roll angle")] + //[FieldOffset(64)] + public float RollAngle; + + /// Roll angle reference [deg] + [Units("[deg]")] + [Description("Roll angle reference")] + //[FieldOffset(68)] + public float RollAngleRef; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(72)] + public float p; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(76)] + public float pRef; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(80)] + public float r; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(84)] + public float rRef; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(88)] + public float uAil; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(92)] + public float uRud; + + /// ASLCTRL control-mode (manual, stabilized, auto, etc...) + [Units("")] + [Description(" ASLCTRL control-mode (manual, stabilized, auto, etc...)")] + //[FieldOffset(96)] + public byte aslctrl_mode; + + /// + [Units("")] + [Description(" ")] + //[FieldOffset(97)] + public byte SpoilersEngaged; }; - /// extensions_start 13 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=47)] - /// Camera Capture Feedback. - public struct mavlink_camera_feedback_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] + /// ASL-fixed-wing controller debug data + public struct mavlink_aslctrl_debug_t { /// packet ordered constructor - public mavlink_camera_feedback_t(ulong time_usec,int lat,int lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,ushort img_idx,byte target_system,byte cam_idx,/*CAMERA_FEEDBACK_FLAGS*/byte flags,ushort completed_captures) + public mavlink_aslctrl_debug_t(uint i32_1,float f_1,float f_2,float f_3,float f_4,float f_5,float f_6,float f_7,float f_8,byte i8_1,byte i8_2) { - this.time_usec = time_usec; - this.lat = lat; - this.lng = lng; - this.alt_msl = alt_msl; - this.alt_rel = alt_rel; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.foc_len = foc_len; - this.img_idx = img_idx; - this.target_system = target_system; - this.cam_idx = cam_idx; - this.flags = flags; - this.completed_captures = completed_captures; + this.i32_1 = i32_1; + this.f_1 = f_1; + this.f_2 = f_2; + this.f_3 = f_3; + this.f_4 = f_4; + this.f_5 = f_5; + this.f_6 = f_6; + this.f_7 = f_7; + this.f_8 = f_8; + this.i8_1 = i8_1; + this.i8_2 = i8_2; } /// packet xml order - public static mavlink_camera_feedback_t PopulateXMLOrder(ulong time_usec,byte target_system,byte cam_idx,ushort img_idx,int lat,int lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,/*CAMERA_FEEDBACK_FLAGS*/byte flags,ushort completed_captures) + public static mavlink_aslctrl_debug_t PopulateXMLOrder(uint i32_1,byte i8_1,byte i8_2,float f_1,float f_2,float f_3,float f_4,float f_5,float f_6,float f_7,float f_8) { - var msg = new mavlink_camera_feedback_t(); + var msg = new mavlink_aslctrl_debug_t(); - msg.time_usec = time_usec; - msg.target_system = target_system; - msg.cam_idx = cam_idx; - msg.img_idx = img_idx; - msg.lat = lat; - msg.lng = lng; - msg.alt_msl = alt_msl; - msg.alt_rel = alt_rel; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.foc_len = foc_len; - msg.flags = flags; - msg.completed_captures = completed_captures; + msg.i32_1 = i32_1; + msg.i8_1 = i8_1; + msg.i8_2 = i8_2; + msg.f_1 = f_1; + msg.f_2 = f_2; + msg.f_3 = f_3; + msg.f_4 = f_4; + msg.f_5 = f_5; + msg.f_6 = f_6; + msg.f_7 = f_7; + msg.f_8 = f_8; return msg; } - /// Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB). [us] - [Units("[us]")] - [Description("Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(0)] - public ulong time_usec; + public uint i32_1; - /// Latitude. [degE7] - [Units("[degE7]")] - [Description("Latitude.")] + /// Debug data + [Units("")] + [Description(" Debug data ")] + //[FieldOffset(4)] + public float f_1; + + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(8)] - public int lat; + public float f_2; - /// Longitude. [degE7] - [Units("[degE7]")] - [Description("Longitude.")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(12)] - public int lng; + public float f_3; - /// Altitude (MSL). [m] - [Units("[m]")] - [Description("Altitude (MSL).")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(16)] - public float alt_msl; + public float f_4; - /// Altitude (Relative to HOME location). [m] - [Units("[m]")] - [Description("Altitude (Relative to HOME location).")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(20)] - public float alt_rel; + public float f_5; - /// Camera Roll angle (earth frame, +-180). [deg] - [Units("[deg]")] - [Description("Camera Roll angle (earth frame, +-180).")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(24)] - public float roll; + public float f_6; - /// Camera Pitch angle (earth frame, +-180). [deg] - [Units("[deg]")] - [Description("Camera Pitch angle (earth frame, +-180).")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(28)] - public float pitch; + public float f_7; - /// Camera Yaw (earth frame, 0-360, true). [deg] - [Units("[deg]")] - [Description("Camera Yaw (earth frame, 0-360, true).")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(32)] - public float yaw; + public float f_8; - /// Focal Length. [mm] - [Units("[mm]")] - [Description("Focal Length.")] + /// Debug data + [Units("")] + [Description(" Debug data")] //[FieldOffset(36)] - public float foc_len; + public byte i8_1; - /// Image index. + /// Debug data [Units("")] - [Description("Image index.")] - //[FieldOffset(40)] - public ushort img_idx; + [Description(" Debug data")] + //[FieldOffset(37)] + public byte i8_2; + }; - /// System ID. + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// Extended state information for ASLUAVs + public struct mavlink_asluav_status_t + { + /// packet ordered constructor + public mavlink_asluav_status_t(float Motor_rpm,byte LED_status,byte SATCOM_status,byte[] Servo_status) + { + this.Motor_rpm = Motor_rpm; + this.LED_status = LED_status; + this.SATCOM_status = SATCOM_status; + this.Servo_status = Servo_status; + + } + + /// packet xml order + public static mavlink_asluav_status_t PopulateXMLOrder(byte LED_status,byte SATCOM_status,byte[] Servo_status,float Motor_rpm) + { + var msg = new mavlink_asluav_status_t(); + + msg.LED_status = LED_status; + msg.SATCOM_status = SATCOM_status; + msg.Servo_status = Servo_status; + msg.Motor_rpm = Motor_rpm; + + return msg; + } + + + /// Motor RPM [Units("")] - [Description("System ID.")] - //[FieldOffset(42)] - public byte target_system; + [Description(" Motor RPM ")] + //[FieldOffset(0)] + public float Motor_rpm; - /// Camera ID. + /// Status of the position-indicator LEDs [Units("")] - [Description("Camera ID.")] - //[FieldOffset(43)] - public byte cam_idx; + [Description(" Status of the position-indicator LEDs")] + //[FieldOffset(4)] + public byte LED_status; - /// Feedback flags. CAMERA_FEEDBACK_FLAGS + /// Status of the IRIDIUM satellite communication system [Units("")] - [Description("Feedback flags.")] - //[FieldOffset(44)] - public /*CAMERA_FEEDBACK_FLAGS*/byte flags; + [Description(" Status of the IRIDIUM satellite communication system")] + //[FieldOffset(5)] + public byte SATCOM_status; - /// Completed image captures. + /// Status vector for up to 8 servos [Units("")] - [Description("Completed image captures.")] - //[FieldOffset(45)] - public ushort completed_captures; + [Description(" Status vector for up to 8 servos")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] Servo_status; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - /// 2nd Battery status - public struct mavlink_battery2_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] + /// Extended EKF state estimates for ASLUAVs + public struct mavlink_ekf_ext_t { /// packet ordered constructor - public mavlink_battery2_t(ushort voltage,short current_battery) + public mavlink_ekf_ext_t(ulong timestamp,float Windspeed,float WindDir,float WindZ,float Airspeed,float beta,float alpha) { - this.voltage = voltage; - this.current_battery = current_battery; + this.timestamp = timestamp; + this.Windspeed = Windspeed; + this.WindDir = WindDir; + this.WindZ = WindZ; + this.Airspeed = Airspeed; + this.beta = beta; + this.alpha = alpha; } /// packet xml order - public static mavlink_battery2_t PopulateXMLOrder(ushort voltage,short current_battery) + public static mavlink_ekf_ext_t PopulateXMLOrder(ulong timestamp,float Windspeed,float WindDir,float WindZ,float Airspeed,float beta,float alpha) { - var msg = new mavlink_battery2_t(); + var msg = new mavlink_ekf_ext_t(); - msg.voltage = voltage; - msg.current_battery = current_battery; + msg.timestamp = timestamp; + msg.Windspeed = Windspeed; + msg.WindDir = WindDir; + msg.WindZ = WindZ; + msg.Airspeed = Airspeed; + msg.beta = beta; + msg.alpha = alpha; return msg; } - /// Voltage. [mV] - [Units("[mV]")] - [Description("Voltage.")] + /// Time since system start [us] + [Units("[us]")] + [Description(" Time since system start")] //[FieldOffset(0)] - public ushort voltage; + public ulong timestamp; - /// Battery current, -1: autopilot does not measure the current. [cA] - [Units("[cA]")] - [Description("Battery current, -1: autopilot does not measure the current.")] - //[FieldOffset(2)] - public short current_battery; + /// Magnitude of wind velocity (in lateral inertial plane) [m/s] + [Units("[m/s]")] + [Description(" Magnitude of wind velocity (in lateral inertial plane)")] + //[FieldOffset(8)] + public float Windspeed; + + /// Wind heading angle from North [rad] + [Units("[rad]")] + [Description(" Wind heading angle from North")] + //[FieldOffset(12)] + public float WindDir; + + /// Z (Down) component of inertial wind velocity [m/s] + [Units("[m/s]")] + [Description(" Z (Down) component of inertial wind velocity")] + //[FieldOffset(16)] + public float WindZ; + + /// Magnitude of air velocity [m/s] + [Units("[m/s]")] + [Description(" Magnitude of air velocity")] + //[FieldOffset(20)] + public float Airspeed; + + /// Sideslip angle [rad] + [Units("[rad]")] + [Description(" Sideslip angle")] + //[FieldOffset(24)] + public float beta; + + /// Angle of attack [rad] + [Units("[rad]")] + [Description(" Angle of attack")] + //[FieldOffset(28)] + public float alpha; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] - /// Status of third AHRS filter if available. This is for ANU research group (Ali and Sean). - public struct mavlink_ahrs3_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// Off-board controls/commands for ASLUAVs + public struct mavlink_asl_obctrl_t { /// packet ordered constructor - public mavlink_ahrs3_t(float roll,float pitch,float yaw,float altitude,int lat,int lng,float v1,float v2,float v3,float v4) + public mavlink_asl_obctrl_t(ulong timestamp,float uElev,float uThrot,float uThrot2,float uAilL,float uAilR,float uRud,byte obctrl_status) { - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.altitude = altitude; - this.lat = lat; - this.lng = lng; - this.v1 = v1; - this.v2 = v2; - this.v3 = v3; - this.v4 = v4; + this.timestamp = timestamp; + this.uElev = uElev; + this.uThrot = uThrot; + this.uThrot2 = uThrot2; + this.uAilL = uAilL; + this.uAilR = uAilR; + this.uRud = uRud; + this.obctrl_status = obctrl_status; } /// packet xml order - public static mavlink_ahrs3_t PopulateXMLOrder(float roll,float pitch,float yaw,float altitude,int lat,int lng,float v1,float v2,float v3,float v4) + public static mavlink_asl_obctrl_t PopulateXMLOrder(ulong timestamp,float uElev,float uThrot,float uThrot2,float uAilL,float uAilR,float uRud,byte obctrl_status) { - var msg = new mavlink_ahrs3_t(); + var msg = new mavlink_asl_obctrl_t(); - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.altitude = altitude; - msg.lat = lat; - msg.lng = lng; - msg.v1 = v1; - msg.v2 = v2; - msg.v3 = v3; - msg.v4 = v4; + msg.timestamp = timestamp; + msg.uElev = uElev; + msg.uThrot = uThrot; + msg.uThrot2 = uThrot2; + msg.uAilL = uAilL; + msg.uAilR = uAilR; + msg.uRud = uRud; + msg.obctrl_status = obctrl_status; return msg; } - /// Roll angle. [rad] - [Units("[rad]")] - [Description("Roll angle.")] - //[FieldOffset(0)] - public float roll; - - /// Pitch angle. [rad] - [Units("[rad]")] - [Description("Pitch angle.")] - //[FieldOffset(4)] - public float pitch; + /// Time since system start [us] + [Units("[us]")] + [Description(" Time since system start")] + //[FieldOffset(0)] + public ulong timestamp; - /// Yaw angle. [rad] - [Units("[rad]")] - [Description("Yaw angle.")] + /// Elevator command [~] + [Units("")] + [Description(" Elevator command [~]")] //[FieldOffset(8)] - public float yaw; + public float uElev; - /// Altitude (MSL). [m] - [Units("[m]")] - [Description("Altitude (MSL).")] + /// Throttle command [~] + [Units("")] + [Description(" Throttle command [~]")] //[FieldOffset(12)] - public float altitude; + public float uThrot; - /// Latitude. [degE7] - [Units("[degE7]")] - [Description("Latitude.")] + /// Throttle 2 command [~] + [Units("")] + [Description(" Throttle 2 command [~]")] //[FieldOffset(16)] - public int lat; + public float uThrot2; - /// Longitude. [degE7] - [Units("[degE7]")] - [Description("Longitude.")] + /// Left aileron command [~] + [Units("")] + [Description(" Left aileron command [~]")] //[FieldOffset(20)] - public int lng; + public float uAilL; - /// Test variable1. + /// Right aileron command [~] [Units("")] - [Description("Test variable1.")] + [Description(" Right aileron command [~]")] //[FieldOffset(24)] - public float v1; + public float uAilR; - /// Test variable2. + /// Rudder command [~] [Units("")] - [Description("Test variable2.")] + [Description(" Rudder command [~]")] //[FieldOffset(28)] - public float v2; + public float uRud; - /// Test variable3. + /// Off-board computer status [Units("")] - [Description("Test variable3.")] + [Description(" Off-board computer status")] //[FieldOffset(32)] - public float v3; - - /// Test variable4. - [Units("")] - [Description("Test variable4.")] - //[FieldOffset(36)] - public float v4; + public byte obctrl_status; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Request the autopilot version from the system/component. - public struct mavlink_autopilot_version_request_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Atmospheric sensors (temperature, humidity, ...) + public struct mavlink_sens_atmos_t { /// packet ordered constructor - public mavlink_autopilot_version_request_t(byte target_system,byte target_component) + public mavlink_sens_atmos_t(ulong timestamp,float TempAmbient,float Humidity) { - this.target_system = target_system; - this.target_component = target_component; + this.timestamp = timestamp; + this.TempAmbient = TempAmbient; + this.Humidity = Humidity; } /// packet xml order - public static mavlink_autopilot_version_request_t PopulateXMLOrder(byte target_system,byte target_component) + public static mavlink_sens_atmos_t PopulateXMLOrder(ulong timestamp,float TempAmbient,float Humidity) { - var msg = new mavlink_autopilot_version_request_t(); + var msg = new mavlink_sens_atmos_t(); - msg.target_system = target_system; - msg.target_component = target_component; + msg.timestamp = timestamp; + msg.TempAmbient = TempAmbient; + msg.Humidity = Humidity; return msg; } - /// System ID. - [Units("")] - [Description("System ID.")] + /// Time since system boot [us] + [Units("[us]")] + [Description("Time since system boot")] //[FieldOffset(0)] - public byte target_system; + public ulong timestamp; - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(1)] - public byte target_component; + /// Ambient temperature [degC] + [Units("[degC]")] + [Description(" Ambient temperature")] + //[FieldOffset(8)] + public float TempAmbient; + + /// Relative humidity [%] + [Units("[%]")] + [Description(" Relative humidity")] + //[FieldOffset(12)] + public float Humidity; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=206)] - /// Send a block of log data to remote location. - public struct mavlink_remote_log_data_block_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=41)] + /// Battery pack monitoring data for Li-Ion batteries + public struct mavlink_sens_batmon_t { /// packet ordered constructor - public mavlink_remote_log_data_block_t(/*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS*/uint seqno,byte target_system,byte target_component,byte[] data) + public mavlink_sens_batmon_t(ulong batmon_timestamp,float temperature,uint safetystatus,uint operationstatus,ushort voltage,short current,ushort batterystatus,ushort serialnumber,ushort cellvoltage1,ushort cellvoltage2,ushort cellvoltage3,ushort cellvoltage4,ushort cellvoltage5,ushort cellvoltage6,byte SoC) { - this.seqno = seqno; - this.target_system = target_system; - this.target_component = target_component; - this.data = data; + this.batmon_timestamp = batmon_timestamp; + this.temperature = temperature; + this.safetystatus = safetystatus; + this.operationstatus = operationstatus; + this.voltage = voltage; + this.current = current; + this.batterystatus = batterystatus; + this.serialnumber = serialnumber; + this.cellvoltage1 = cellvoltage1; + this.cellvoltage2 = cellvoltage2; + this.cellvoltage3 = cellvoltage3; + this.cellvoltage4 = cellvoltage4; + this.cellvoltage5 = cellvoltage5; + this.cellvoltage6 = cellvoltage6; + this.SoC = SoC; } /// packet xml order - public static mavlink_remote_log_data_block_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS*/uint seqno,byte[] data) + public static mavlink_sens_batmon_t PopulateXMLOrder(ulong batmon_timestamp,float temperature,ushort voltage,short current,byte SoC,ushort batterystatus,ushort serialnumber,uint safetystatus,uint operationstatus,ushort cellvoltage1,ushort cellvoltage2,ushort cellvoltage3,ushort cellvoltage4,ushort cellvoltage5,ushort cellvoltage6) { - var msg = new mavlink_remote_log_data_block_t(); + var msg = new mavlink_sens_batmon_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.seqno = seqno; - msg.data = data; + msg.batmon_timestamp = batmon_timestamp; + msg.temperature = temperature; + msg.voltage = voltage; + msg.current = current; + msg.SoC = SoC; + msg.batterystatus = batterystatus; + msg.serialnumber = serialnumber; + msg.safetystatus = safetystatus; + msg.operationstatus = operationstatus; + msg.cellvoltage1 = cellvoltage1; + msg.cellvoltage2 = cellvoltage2; + msg.cellvoltage3 = cellvoltage3; + msg.cellvoltage4 = cellvoltage4; + msg.cellvoltage5 = cellvoltage5; + msg.cellvoltage6 = cellvoltage6; return msg; } - /// Log data block sequence number. MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS - [Units("")] - [Description("Log data block sequence number.")] + /// Time since system start [us] + [Units("[us]")] + [Description("Time since system start")] //[FieldOffset(0)] - public /*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS*/uint seqno; + public ulong batmon_timestamp; - /// System ID. + /// Battery pack temperature [degC] + [Units("[degC]")] + [Description("Battery pack temperature")] + //[FieldOffset(8)] + public float temperature; + + /// Battery monitor safetystatus report bits in Hex [Units("")] - [Description("System ID.")] - //[FieldOffset(4)] - public byte target_system; + [Description("Battery monitor safetystatus report bits in Hex")] + //[FieldOffset(12)] + public uint safetystatus; - /// Component ID. + /// Battery monitor operation status report bits in Hex [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + [Description("Battery monitor operation status report bits in Hex")] + //[FieldOffset(16)] + public uint operationstatus; - /// Log data block. + /// Battery pack voltage [mV] + [Units("[mV]")] + [Description("Battery pack voltage")] + //[FieldOffset(20)] + public ushort voltage; + + /// Battery pack current [mA] + [Units("[mA]")] + [Description("Battery pack current")] + //[FieldOffset(22)] + public short current; + + /// Battery monitor status report bits in Hex [Units("")] - [Description("Log data block.")] - //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=200)] - public byte[] data; + [Description("Battery monitor status report bits in Hex")] + //[FieldOffset(24)] + public ushort batterystatus; + + /// Battery monitor serial number in Hex + [Units("")] + [Description("Battery monitor serial number in Hex")] + //[FieldOffset(26)] + public ushort serialnumber; + + /// Battery pack cell 1 voltage [mV] + [Units("[mV]")] + [Description("Battery pack cell 1 voltage")] + //[FieldOffset(28)] + public ushort cellvoltage1; + + /// Battery pack cell 2 voltage [mV] + [Units("[mV]")] + [Description("Battery pack cell 2 voltage")] + //[FieldOffset(30)] + public ushort cellvoltage2; + + /// Battery pack cell 3 voltage [mV] + [Units("[mV]")] + [Description("Battery pack cell 3 voltage")] + //[FieldOffset(32)] + public ushort cellvoltage3; + + /// Battery pack cell 4 voltage [mV] + [Units("[mV]")] + [Description("Battery pack cell 4 voltage")] + //[FieldOffset(34)] + public ushort cellvoltage4; + + /// Battery pack cell 5 voltage [mV] + [Units("[mV]")] + [Description("Battery pack cell 5 voltage")] + //[FieldOffset(36)] + public ushort cellvoltage5; + + /// Battery pack cell 6 voltage [mV] + [Units("[mV]")] + [Description("Battery pack cell 6 voltage")] + //[FieldOffset(38)] + public ushort cellvoltage6; + + /// Battery pack state-of-charge + [Units("")] + [Description("Battery pack state-of-charge")] + //[FieldOffset(40)] + public byte SoC; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] - /// Send Status of each log block that autopilot board might have sent. - public struct mavlink_remote_log_block_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=102)] + /// Fixed-wing soaring (i.e. thermal seeking) data + public struct mavlink_fw_soaring_data_t { /// packet ordered constructor - public mavlink_remote_log_block_status_t(uint seqno,byte target_system,byte target_component,/*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES*/byte status) - { - this.seqno = seqno; - this.target_system = target_system; - this.target_component = target_component; - this.status = status; - - } - - /// packet xml order - public static mavlink_remote_log_block_status_t PopulateXMLOrder(byte target_system,byte target_component,uint seqno,/*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES*/byte status) + public mavlink_fw_soaring_data_t(ulong timestamp,ulong timestampModeChanged,float xW,float xR,float xLat,float xLon,float VarW,float VarR,float VarLat,float VarLon,float LoiterRadius,float LoiterDirection,float DistToSoarPoint,float vSinkExp,float z1_LocalUpdraftSpeed,float z2_DeltaRoll,float z1_exp,float z2_exp,float ThermalGSNorth,float ThermalGSEast,float TSE_dot,float DebugVar1,float DebugVar2,byte ControlMode,byte valid) { - var msg = new mavlink_remote_log_block_status_t(); + this.timestamp = timestamp; + this.timestampModeChanged = timestampModeChanged; + this.xW = xW; + this.xR = xR; + this.xLat = xLat; + this.xLon = xLon; + this.VarW = VarW; + this.VarR = VarR; + this.VarLat = VarLat; + this.VarLon = VarLon; + this.LoiterRadius = LoiterRadius; + this.LoiterDirection = LoiterDirection; + this.DistToSoarPoint = DistToSoarPoint; + this.vSinkExp = vSinkExp; + this.z1_LocalUpdraftSpeed = z1_LocalUpdraftSpeed; + this.z2_DeltaRoll = z2_DeltaRoll; + this.z1_exp = z1_exp; + this.z2_exp = z2_exp; + this.ThermalGSNorth = ThermalGSNorth; + this.ThermalGSEast = ThermalGSEast; + this.TSE_dot = TSE_dot; + this.DebugVar1 = DebugVar1; + this.DebugVar2 = DebugVar2; + this.ControlMode = ControlMode; + this.valid = valid; + + } + + /// packet xml order + public static mavlink_fw_soaring_data_t PopulateXMLOrder(ulong timestamp,ulong timestampModeChanged,float xW,float xR,float xLat,float xLon,float VarW,float VarR,float VarLat,float VarLon,float LoiterRadius,float LoiterDirection,float DistToSoarPoint,float vSinkExp,float z1_LocalUpdraftSpeed,float z2_DeltaRoll,float z1_exp,float z2_exp,float ThermalGSNorth,float ThermalGSEast,float TSE_dot,float DebugVar1,float DebugVar2,byte ControlMode,byte valid) + { + var msg = new mavlink_fw_soaring_data_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.seqno = seqno; - msg.status = status; - - return msg; - } - + msg.timestamp = timestamp; + msg.timestampModeChanged = timestampModeChanged; + msg.xW = xW; + msg.xR = xR; + msg.xLat = xLat; + msg.xLon = xLon; + msg.VarW = VarW; + msg.VarR = VarR; + msg.VarLat = VarLat; + msg.VarLon = VarLon; + msg.LoiterRadius = LoiterRadius; + msg.LoiterDirection = LoiterDirection; + msg.DistToSoarPoint = DistToSoarPoint; + msg.vSinkExp = vSinkExp; + msg.z1_LocalUpdraftSpeed = z1_LocalUpdraftSpeed; + msg.z2_DeltaRoll = z2_DeltaRoll; + msg.z1_exp = z1_exp; + msg.z2_exp = z2_exp; + msg.ThermalGSNorth = ThermalGSNorth; + msg.ThermalGSEast = ThermalGSEast; + msg.TSE_dot = TSE_dot; + msg.DebugVar1 = DebugVar1; + msg.DebugVar2 = DebugVar2; + msg.ControlMode = ControlMode; + msg.valid = valid; + + return msg; + } + + + /// Timestamp [ms] + [Units("[ms]")] + [Description("Timestamp")] + //[FieldOffset(0)] + public ulong timestamp; - /// Log data block sequence number. + /// Timestamp since last mode change [ms] + [Units("[ms]")] + [Description("Timestamp since last mode change")] + //[FieldOffset(8)] + public ulong timestampModeChanged; + + /// Thermal core updraft strength [m/s] + [Units("[m/s]")] + [Description("Thermal core updraft strength")] + //[FieldOffset(16)] + public float xW; + + /// Thermal radius [m] + [Units("[m]")] + [Description("Thermal radius")] + //[FieldOffset(20)] + public float xR; + + /// Thermal center latitude [deg] + [Units("[deg]")] + [Description("Thermal center latitude")] + //[FieldOffset(24)] + public float xLat; + + /// Thermal center longitude [deg] + [Units("[deg]")] + [Description("Thermal center longitude")] + //[FieldOffset(28)] + public float xLon; + + /// Variance W [Units("")] - [Description("Log data block sequence number.")] - //[FieldOffset(0)] - public uint seqno; + [Description("Variance W")] + //[FieldOffset(32)] + public float VarW; - /// System ID. + /// Variance R [Units("")] - [Description("System ID.")] - //[FieldOffset(4)] - public byte target_system; + [Description("Variance R")] + //[FieldOffset(36)] + public float VarR; - /// Component ID. + /// Variance Lat [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + [Description("Variance Lat")] + //[FieldOffset(40)] + public float VarLat; - /// Log data block status. MAV_REMOTE_LOG_DATA_BLOCK_STATUSES + /// Variance Lon [Units("")] - [Description("Log data block status.")] - //[FieldOffset(6)] - public /*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES*/byte status; + [Description("Variance Lon ")] + //[FieldOffset(44)] + public float VarLon; + + /// Suggested loiter radius [m] + [Units("[m]")] + [Description("Suggested loiter radius")] + //[FieldOffset(48)] + public float LoiterRadius; + + /// Suggested loiter direction + [Units("")] + [Description("Suggested loiter direction")] + //[FieldOffset(52)] + public float LoiterDirection; + + /// Distance to soar point [m] + [Units("[m]")] + [Description("Distance to soar point")] + //[FieldOffset(56)] + public float DistToSoarPoint; + + /// Expected sink rate at current airspeed, roll and throttle [m/s] + [Units("[m/s]")] + [Description("Expected sink rate at current airspeed, roll and throttle")] + //[FieldOffset(60)] + public float vSinkExp; + + /// Measurement / updraft speed at current/local airplane position [m/s] + [Units("[m/s]")] + [Description("Measurement / updraft speed at current/local airplane position")] + //[FieldOffset(64)] + public float z1_LocalUpdraftSpeed; + + /// Measurement / roll angle tracking error [deg] + [Units("[deg]")] + [Description("Measurement / roll angle tracking error")] + //[FieldOffset(68)] + public float z2_DeltaRoll; + + /// Expected measurement 1 + [Units("")] + [Description("Expected measurement 1")] + //[FieldOffset(72)] + public float z1_exp; + + /// Expected measurement 2 + [Units("")] + [Description("Expected measurement 2")] + //[FieldOffset(76)] + public float z2_exp; + + /// Thermal drift (from estimator prediction step only) [m/s] + [Units("[m/s]")] + [Description("Thermal drift (from estimator prediction step only)")] + //[FieldOffset(80)] + public float ThermalGSNorth; + + /// Thermal drift (from estimator prediction step only) [m/s] + [Units("[m/s]")] + [Description("Thermal drift (from estimator prediction step only)")] + //[FieldOffset(84)] + public float ThermalGSEast; + + /// Total specific energy change (filtered) [m/s] + [Units("[m/s]")] + [Description(" Total specific energy change (filtered)")] + //[FieldOffset(88)] + public float TSE_dot; + + /// Debug variable 1 + [Units("")] + [Description(" Debug variable 1")] + //[FieldOffset(92)] + public float DebugVar1; + + /// Debug variable 2 + [Units("")] + [Description(" Debug variable 2")] + //[FieldOffset(96)] + public float DebugVar2; + + /// Control Mode [-] + [Units("")] + [Description("Control Mode [-]")] + //[FieldOffset(100)] + public byte ControlMode; + + /// Data valid [-] + [Units("")] + [Description("Data valid [-]")] + //[FieldOffset(101)] + public byte valid; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=29)] - /// Control vehicle LEDs. - public struct mavlink_led_control_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Monitoring of sensorpod status + public struct mavlink_sensorpod_status_t { /// packet ordered constructor - public mavlink_led_control_t(byte target_system,byte target_component,byte instance,byte pattern,byte custom_len,byte[] custom_bytes) + public mavlink_sensorpod_status_t(ulong timestamp,ushort free_space,byte visensor_rate_1,byte visensor_rate_2,byte visensor_rate_3,byte visensor_rate_4,byte recording_nodes_count,byte cpu_temp) { - this.target_system = target_system; - this.target_component = target_component; - this.instance = instance; - this.pattern = pattern; - this.custom_len = custom_len; - this.custom_bytes = custom_bytes; + this.timestamp = timestamp; + this.free_space = free_space; + this.visensor_rate_1 = visensor_rate_1; + this.visensor_rate_2 = visensor_rate_2; + this.visensor_rate_3 = visensor_rate_3; + this.visensor_rate_4 = visensor_rate_4; + this.recording_nodes_count = recording_nodes_count; + this.cpu_temp = cpu_temp; } /// packet xml order - public static mavlink_led_control_t PopulateXMLOrder(byte target_system,byte target_component,byte instance,byte pattern,byte custom_len,byte[] custom_bytes) + public static mavlink_sensorpod_status_t PopulateXMLOrder(ulong timestamp,byte visensor_rate_1,byte visensor_rate_2,byte visensor_rate_3,byte visensor_rate_4,byte recording_nodes_count,byte cpu_temp,ushort free_space) { - var msg = new mavlink_led_control_t(); + var msg = new mavlink_sensorpod_status_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.instance = instance; - msg.pattern = pattern; - msg.custom_len = custom_len; - msg.custom_bytes = custom_bytes; + msg.timestamp = timestamp; + msg.visensor_rate_1 = visensor_rate_1; + msg.visensor_rate_2 = visensor_rate_2; + msg.visensor_rate_3 = visensor_rate_3; + msg.visensor_rate_4 = visensor_rate_4; + msg.recording_nodes_count = recording_nodes_count; + msg.cpu_temp = cpu_temp; + msg.free_space = free_space; return msg; } - /// System ID. - [Units("")] - [Description("System ID.")] + /// Timestamp in linuxtime (since 1.1.1970) [ms] + [Units("[ms]")] + [Description("Timestamp in linuxtime (since 1.1.1970)")] //[FieldOffset(0)] - public byte target_system; + public ulong timestamp; - /// Component ID. + /// Free space available in recordings directory in [Gb] * 1e2 [Units("")] - [Description("Component ID.")] - //[FieldOffset(1)] - public byte target_component; + [Description("Free space available in recordings directory in [Gb] * 1e2")] + //[FieldOffset(8)] + public ushort free_space; - /// Instance (LED instance to control or 255 for all LEDs). + /// Rate of ROS topic 1 [Units("")] - [Description("Instance (LED instance to control or 255 for all LEDs).")] - //[FieldOffset(2)] - public byte instance; + [Description("Rate of ROS topic 1")] + //[FieldOffset(10)] + public byte visensor_rate_1; - /// Pattern (see LED_PATTERN_ENUM). + /// Rate of ROS topic 2 [Units("")] - [Description("Pattern (see LED_PATTERN_ENUM).")] - //[FieldOffset(3)] - public byte pattern; + [Description("Rate of ROS topic 2")] + //[FieldOffset(11)] + public byte visensor_rate_2; - /// Custom Byte Length. + /// Rate of ROS topic 3 [Units("")] - [Description("Custom Byte Length.")] - //[FieldOffset(4)] - public byte custom_len; + [Description("Rate of ROS topic 3")] + //[FieldOffset(12)] + public byte visensor_rate_3; - /// Custom Bytes. + /// Rate of ROS topic 4 [Units("")] - [Description("Custom Bytes.")] - //[FieldOffset(5)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=24)] - public byte[] custom_bytes; + [Description("Rate of ROS topic 4")] + //[FieldOffset(13)] + public byte visensor_rate_4; + + /// Number of recording nodes + [Units("")] + [Description("Number of recording nodes")] + //[FieldOffset(14)] + public byte recording_nodes_count; + + /// Temperature of sensorpod CPU in [degC] + [Units("[degC]")] + [Description("Temperature of sensorpod CPU in")] + //[FieldOffset(15)] + public byte cpu_temp; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)] - /// Reports progress of compass calibration. - public struct mavlink_mag_cal_progress_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] + /// Monitoring of power board status + public struct mavlink_sens_power_board_t { /// packet ordered constructor - public mavlink_mag_cal_progress_t(float direction_x,float direction_y,float direction_z,byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte attempt,byte completion_pct,byte[] completion_mask) + public mavlink_sens_power_board_t(ulong timestamp,float pwr_brd_system_volt,float pwr_brd_servo_volt,float pwr_brd_digital_volt,float pwr_brd_mot_l_amp,float pwr_brd_mot_r_amp,float pwr_brd_analog_amp,float pwr_brd_digital_amp,float pwr_brd_ext_amp,float pwr_brd_aux_amp,byte pwr_brd_status,byte pwr_brd_led_status) { - this.direction_x = direction_x; - this.direction_y = direction_y; - this.direction_z = direction_z; - this.compass_id = compass_id; - this.cal_mask = cal_mask; - this.cal_status = cal_status; - this.attempt = attempt; - this.completion_pct = completion_pct; - this.completion_mask = completion_mask; + this.timestamp = timestamp; + this.pwr_brd_system_volt = pwr_brd_system_volt; + this.pwr_brd_servo_volt = pwr_brd_servo_volt; + this.pwr_brd_digital_volt = pwr_brd_digital_volt; + this.pwr_brd_mot_l_amp = pwr_brd_mot_l_amp; + this.pwr_brd_mot_r_amp = pwr_brd_mot_r_amp; + this.pwr_brd_analog_amp = pwr_brd_analog_amp; + this.pwr_brd_digital_amp = pwr_brd_digital_amp; + this.pwr_brd_ext_amp = pwr_brd_ext_amp; + this.pwr_brd_aux_amp = pwr_brd_aux_amp; + this.pwr_brd_status = pwr_brd_status; + this.pwr_brd_led_status = pwr_brd_led_status; } /// packet xml order - public static mavlink_mag_cal_progress_t PopulateXMLOrder(byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte attempt,byte completion_pct,byte[] completion_mask,float direction_x,float direction_y,float direction_z) + public static mavlink_sens_power_board_t PopulateXMLOrder(ulong timestamp,byte pwr_brd_status,byte pwr_brd_led_status,float pwr_brd_system_volt,float pwr_brd_servo_volt,float pwr_brd_digital_volt,float pwr_brd_mot_l_amp,float pwr_brd_mot_r_amp,float pwr_brd_analog_amp,float pwr_brd_digital_amp,float pwr_brd_ext_amp,float pwr_brd_aux_amp) { - var msg = new mavlink_mag_cal_progress_t(); + var msg = new mavlink_sens_power_board_t(); - msg.compass_id = compass_id; - msg.cal_mask = cal_mask; - msg.cal_status = cal_status; - msg.attempt = attempt; - msg.completion_pct = completion_pct; - msg.completion_mask = completion_mask; - msg.direction_x = direction_x; - msg.direction_y = direction_y; - msg.direction_z = direction_z; + msg.timestamp = timestamp; + msg.pwr_brd_status = pwr_brd_status; + msg.pwr_brd_led_status = pwr_brd_led_status; + msg.pwr_brd_system_volt = pwr_brd_system_volt; + msg.pwr_brd_servo_volt = pwr_brd_servo_volt; + msg.pwr_brd_digital_volt = pwr_brd_digital_volt; + msg.pwr_brd_mot_l_amp = pwr_brd_mot_l_amp; + msg.pwr_brd_mot_r_amp = pwr_brd_mot_r_amp; + msg.pwr_brd_analog_amp = pwr_brd_analog_amp; + msg.pwr_brd_digital_amp = pwr_brd_digital_amp; + msg.pwr_brd_ext_amp = pwr_brd_ext_amp; + msg.pwr_brd_aux_amp = pwr_brd_aux_amp; return msg; } - /// Body frame direction vector for display. - [Units("")] - [Description("Body frame direction vector for display.")] + /// Timestamp [us] + [Units("[us]")] + [Description("Timestamp")] //[FieldOffset(0)] - public float direction_x; - - /// Body frame direction vector for display. - [Units("")] - [Description("Body frame direction vector for display.")] - //[FieldOffset(4)] - public float direction_y; + public ulong timestamp; - /// Body frame direction vector for display. - [Units("")] - [Description("Body frame direction vector for display.")] + /// Power board system voltage [V] + [Units("[V]")] + [Description("Power board system voltage")] //[FieldOffset(8)] - public float direction_z; + public float pwr_brd_system_volt; - /// Compass being calibrated. - [Units("")] - [Description("Compass being calibrated.")] + /// Power board servo voltage [V] + [Units("[V]")] + [Description("Power board servo voltage")] //[FieldOffset(12)] - public byte compass_id; + public float pwr_brd_servo_volt; - /// Bitmask of compasses being calibrated. bitmask - [Units("")] - [Description("Bitmask of compasses being calibrated.")] - //[FieldOffset(13)] - public byte cal_mask; + /// Power board digital voltage [V] + [Units("[V]")] + [Description("Power board digital voltage")] + //[FieldOffset(16)] + public float pwr_brd_digital_volt; - /// Calibration Status. MAG_CAL_STATUS - [Units("")] - [Description("Calibration Status.")] - //[FieldOffset(14)] - public /*MAG_CAL_STATUS*/byte cal_status; + /// Power board left motor current sensor [A] + [Units("[A]")] + [Description("Power board left motor current sensor")] + //[FieldOffset(20)] + public float pwr_brd_mot_l_amp; - /// Attempt number. - [Units("")] - [Description("Attempt number.")] - //[FieldOffset(15)] - public byte attempt; + /// Power board right motor current sensor [A] + [Units("[A]")] + [Description("Power board right motor current sensor")] + //[FieldOffset(24)] + public float pwr_brd_mot_r_amp; - /// Completion percentage. [%] - [Units("[%]")] - [Description("Completion percentage.")] - //[FieldOffset(16)] - public byte completion_pct; + /// Power board analog current sensor [A] + [Units("[A]")] + [Description("Power board analog current sensor")] + //[FieldOffset(28)] + public float pwr_brd_analog_amp; - /// Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid). + /// Power board digital current sensor [A] + [Units("[A]")] + [Description("Power board digital current sensor")] + //[FieldOffset(32)] + public float pwr_brd_digital_amp; + + /// Power board extension current sensor [A] + [Units("[A]")] + [Description("Power board extension current sensor")] + //[FieldOffset(36)] + public float pwr_brd_ext_amp; + + /// Power board aux current sensor [A] + [Units("[A]")] + [Description("Power board aux current sensor")] + //[FieldOffset(40)] + public float pwr_brd_aux_amp; + + /// Power board status register [Units("")] - [Description("Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).")] - //[FieldOffset(17)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] completion_mask; + [Description("Power board status register")] + //[FieldOffset(44)] + public byte pwr_brd_status; + + /// Power board leds status + [Units("")] + [Description("Power board leds status")] + //[FieldOffset(45)] + public byte pwr_brd_led_status; }; - /// extensions_start 6 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] - /// EKF Status message including flags and variances. - public struct mavlink_ekf_status_report_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// Status of GSM modem (connected to onboard computer) + public struct mavlink_gsm_link_status_t { /// packet ordered constructor - public mavlink_ekf_status_report_t(float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,/*EKF_STATUS_FLAGS*/ushort flags,float airspeed_variance) + public mavlink_gsm_link_status_t(ulong timestamp,/*GSM_MODEM_TYPE*/byte gsm_modem_type,/*GSM_LINK_TYPE*/byte gsm_link_type,byte rssi,byte rsrp_rscp,byte sinr_ecio,byte rsrq) { - this.velocity_variance = velocity_variance; - this.pos_horiz_variance = pos_horiz_variance; - this.pos_vert_variance = pos_vert_variance; - this.compass_variance = compass_variance; - this.terrain_alt_variance = terrain_alt_variance; - this.flags = flags; - this.airspeed_variance = airspeed_variance; + this.timestamp = timestamp; + this.gsm_modem_type = gsm_modem_type; + this.gsm_link_type = gsm_link_type; + this.rssi = rssi; + this.rsrp_rscp = rsrp_rscp; + this.sinr_ecio = sinr_ecio; + this.rsrq = rsrq; } /// packet xml order - public static mavlink_ekf_status_report_t PopulateXMLOrder(/*EKF_STATUS_FLAGS*/ushort flags,float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,float airspeed_variance) + public static mavlink_gsm_link_status_t PopulateXMLOrder(ulong timestamp,/*GSM_MODEM_TYPE*/byte gsm_modem_type,/*GSM_LINK_TYPE*/byte gsm_link_type,byte rssi,byte rsrp_rscp,byte sinr_ecio,byte rsrq) { - var msg = new mavlink_ekf_status_report_t(); + var msg = new mavlink_gsm_link_status_t(); - msg.flags = flags; - msg.velocity_variance = velocity_variance; - msg.pos_horiz_variance = pos_horiz_variance; - msg.pos_vert_variance = pos_vert_variance; - msg.compass_variance = compass_variance; - msg.terrain_alt_variance = terrain_alt_variance; - msg.airspeed_variance = airspeed_variance; + msg.timestamp = timestamp; + msg.gsm_modem_type = gsm_modem_type; + msg.gsm_link_type = gsm_link_type; + msg.rssi = rssi; + msg.rsrp_rscp = rsrp_rscp; + msg.sinr_ecio = sinr_ecio; + msg.rsrq = rsrq; return msg; } - /// Velocity variance. - [Units("")] - [Description("Velocity variance.")] + /// Timestamp (of OBC) [us] + [Units("[us]")] + [Description("Timestamp (of OBC)")] //[FieldOffset(0)] - public float velocity_variance; + public ulong timestamp; - /// Horizontal Position variance. + /// GSM modem used GSM_MODEM_TYPE [Units("")] - [Description("Horizontal Position variance.")] - //[FieldOffset(4)] - public float pos_horiz_variance; + [Description("GSM modem used")] + //[FieldOffset(8)] + public /*GSM_MODEM_TYPE*/byte gsm_modem_type; - /// Vertical Position variance. + /// GSM link type GSM_LINK_TYPE [Units("")] - [Description("Vertical Position variance.")] - //[FieldOffset(8)] - public float pos_vert_variance; + [Description("GSM link type")] + //[FieldOffset(9)] + public /*GSM_LINK_TYPE*/byte gsm_link_type; - /// Compass variance. + /// RSSI as reported by modem (unconverted) [Units("")] - [Description("Compass variance.")] - //[FieldOffset(12)] - public float compass_variance; + [Description("RSSI as reported by modem (unconverted)")] + //[FieldOffset(10)] + public byte rssi; - /// Terrain Altitude variance. + /// RSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted) [Units("")] - [Description("Terrain Altitude variance.")] - //[FieldOffset(16)] - public float terrain_alt_variance; + [Description("RSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted)")] + //[FieldOffset(11)] + public byte rsrp_rscp; - /// Flags. EKF_STATUS_FLAGS bitmask + /// SINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted) [Units("")] - [Description("Flags.")] - //[FieldOffset(20)] - public /*EKF_STATUS_FLAGS*/ushort flags; + [Description("SINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted)")] + //[FieldOffset(12)] + public byte sinr_ecio; - /// Airspeed variance. + /// RSRQ (LTE only) as reported by modem (unconverted) [Units("")] - [Description("Airspeed variance.")] - //[FieldOffset(22)] - public float airspeed_variance; + [Description("RSRQ (LTE only) as reported by modem (unconverted)")] + //[FieldOffset(13)] + public byte rsrq; }; - /// extensions_start 7 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] - /// PID tuning information. - public struct mavlink_pid_tuning_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// Status of the SatCom link + public struct mavlink_satcom_link_status_t { /// packet ordered constructor - public mavlink_pid_tuning_t(float desired,float achieved,float FF,float P,float I,float D,/*PID_TUNING_AXIS*/byte axis,float SRate,float PDmod) + public mavlink_satcom_link_status_t(ulong timestamp,ulong last_heartbeat,ushort failed_sessions,ushort successful_sessions,byte signal_quality,byte ring_pending,byte tx_session_pending,byte rx_session_pending) { - this.desired = desired; - this.achieved = achieved; - this.FF = FF; - this.P = P; - this.I = I; - this.D = D; - this.axis = axis; - this.SRate = SRate; - this.PDmod = PDmod; + this.timestamp = timestamp; + this.last_heartbeat = last_heartbeat; + this.failed_sessions = failed_sessions; + this.successful_sessions = successful_sessions; + this.signal_quality = signal_quality; + this.ring_pending = ring_pending; + this.tx_session_pending = tx_session_pending; + this.rx_session_pending = rx_session_pending; } /// packet xml order - public static mavlink_pid_tuning_t PopulateXMLOrder(/*PID_TUNING_AXIS*/byte axis,float desired,float achieved,float FF,float P,float I,float D,float SRate,float PDmod) + public static mavlink_satcom_link_status_t PopulateXMLOrder(ulong timestamp,ulong last_heartbeat,ushort failed_sessions,ushort successful_sessions,byte signal_quality,byte ring_pending,byte tx_session_pending,byte rx_session_pending) { - var msg = new mavlink_pid_tuning_t(); + var msg = new mavlink_satcom_link_status_t(); - msg.axis = axis; - msg.desired = desired; - msg.achieved = achieved; - msg.FF = FF; - msg.P = P; - msg.I = I; - msg.D = D; - msg.SRate = SRate; - msg.PDmod = PDmod; + msg.timestamp = timestamp; + msg.last_heartbeat = last_heartbeat; + msg.failed_sessions = failed_sessions; + msg.successful_sessions = successful_sessions; + msg.signal_quality = signal_quality; + msg.ring_pending = ring_pending; + msg.tx_session_pending = tx_session_pending; + msg.rx_session_pending = rx_session_pending; return msg; } - /// Desired rate. - [Units("")] - [Description("Desired rate.")] + /// Timestamp [us] + [Units("[us]")] + [Description("Timestamp")] //[FieldOffset(0)] - public float desired; - - /// Achieved rate. - [Units("")] - [Description("Achieved rate.")] - //[FieldOffset(4)] - public float achieved; + public ulong timestamp; - /// FF component. - [Units("")] - [Description("FF component.")] + /// Timestamp of the last successful sbd session [us] + [Units("[us]")] + [Description("Timestamp of the last successful sbd session")] //[FieldOffset(8)] - public float FF; + public ulong last_heartbeat; - /// P component. + /// Number of failed sessions [Units("")] - [Description("P component.")] - //[FieldOffset(12)] - public float P; + [Description("Number of failed sessions")] + //[FieldOffset(16)] + public ushort failed_sessions; - /// I component. + /// Number of successful sessions [Units("")] - [Description("I component.")] - //[FieldOffset(16)] - public float I; + [Description("Number of successful sessions")] + //[FieldOffset(18)] + public ushort successful_sessions; - /// D component. + /// Signal quality [Units("")] - [Description("D component.")] + [Description("Signal quality")] //[FieldOffset(20)] - public float D; + public byte signal_quality; - /// Axis. PID_TUNING_AXIS + /// Ring call pending [Units("")] - [Description("Axis.")] - //[FieldOffset(24)] - public /*PID_TUNING_AXIS*/byte axis; + [Description("Ring call pending")] + //[FieldOffset(21)] + public byte ring_pending; - /// Slew rate. + /// Transmission session pending [Units("")] - [Description("Slew rate.")] - //[FieldOffset(25)] - public float SRate; + [Description("Transmission session pending")] + //[FieldOffset(22)] + public byte tx_session_pending; - /// P/D oscillation modifier. + /// Receiving session pending [Units("")] - [Description("P/D oscillation modifier.")] - //[FieldOffset(29)] - public float PDmod; + [Description("Receiving session pending")] + //[FieldOffset(23)] + public byte rx_session_pending; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - /// Deepstall path planning. - public struct mavlink_deepstall_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] + /// Calibrated airflow angle measurements + public struct mavlink_sensor_airflow_angles_t { /// packet ordered constructor - public mavlink_deepstall_t(int landing_lat,int landing_lon,int path_lat,int path_lon,int arc_entry_lat,int arc_entry_lon,float altitude,float expected_travel_distance,float cross_track_error,/*DEEPSTALL_STAGE*/byte stage) + public mavlink_sensor_airflow_angles_t(ulong timestamp,float angleofattack,float sideslip,byte angleofattack_valid,byte sideslip_valid) { - this.landing_lat = landing_lat; - this.landing_lon = landing_lon; - this.path_lat = path_lat; - this.path_lon = path_lon; - this.arc_entry_lat = arc_entry_lat; - this.arc_entry_lon = arc_entry_lon; - this.altitude = altitude; - this.expected_travel_distance = expected_travel_distance; - this.cross_track_error = cross_track_error; - this.stage = stage; + this.timestamp = timestamp; + this.angleofattack = angleofattack; + this.sideslip = sideslip; + this.angleofattack_valid = angleofattack_valid; + this.sideslip_valid = sideslip_valid; } /// packet xml order - public static mavlink_deepstall_t PopulateXMLOrder(int landing_lat,int landing_lon,int path_lat,int path_lon,int arc_entry_lat,int arc_entry_lon,float altitude,float expected_travel_distance,float cross_track_error,/*DEEPSTALL_STAGE*/byte stage) + public static mavlink_sensor_airflow_angles_t PopulateXMLOrder(ulong timestamp,float angleofattack,byte angleofattack_valid,float sideslip,byte sideslip_valid) { - var msg = new mavlink_deepstall_t(); + var msg = new mavlink_sensor_airflow_angles_t(); - msg.landing_lat = landing_lat; - msg.landing_lon = landing_lon; - msg.path_lat = path_lat; - msg.path_lon = path_lon; - msg.arc_entry_lat = arc_entry_lat; - msg.arc_entry_lon = arc_entry_lon; - msg.altitude = altitude; - msg.expected_travel_distance = expected_travel_distance; - msg.cross_track_error = cross_track_error; - msg.stage = stage; + msg.timestamp = timestamp; + msg.angleofattack = angleofattack; + msg.angleofattack_valid = angleofattack_valid; + msg.sideslip = sideslip; + msg.sideslip_valid = sideslip_valid; return msg; } - /// Landing latitude. [degE7] - [Units("[degE7]")] - [Description("Landing latitude.")] + /// Timestamp [us] + [Units("[us]")] + [Description("Timestamp")] //[FieldOffset(0)] - public int landing_lat; - - /// Landing longitude. [degE7] - [Units("[degE7]")] - [Description("Landing longitude.")] - //[FieldOffset(4)] - public int landing_lon; + public ulong timestamp; - /// Final heading start point, latitude. [degE7] - [Units("[degE7]")] - [Description("Final heading start point, latitude.")] + /// Angle of attack [deg] + [Units("[deg]")] + [Description("Angle of attack")] //[FieldOffset(8)] - public int path_lat; + public float angleofattack; - /// Final heading start point, longitude. [degE7] - [Units("[degE7]")] - [Description("Final heading start point, longitude.")] + /// Sideslip angle [deg] + [Units("[deg]")] + [Description("Sideslip angle")] //[FieldOffset(12)] - public int path_lon; + public float sideslip; - /// Arc entry point, latitude. [degE7] - [Units("[degE7]")] - [Description("Arc entry point, latitude.")] + /// Angle of attack measurement valid + [Units("")] + [Description("Angle of attack measurement valid")] //[FieldOffset(16)] - public int arc_entry_lat; - - /// Arc entry point, longitude. [degE7] - [Units("[degE7]")] - [Description("Arc entry point, longitude.")] - //[FieldOffset(20)] - public int arc_entry_lon; - - /// Altitude. [m] - [Units("[m]")] - [Description("Altitude.")] - //[FieldOffset(24)] - public float altitude; - - /// Distance the aircraft expects to travel during the deepstall. [m] - [Units("[m]")] - [Description("Distance the aircraft expects to travel during the deepstall.")] - //[FieldOffset(28)] - public float expected_travel_distance; - - /// Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND). [m] - [Units("[m]")] - [Description("Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).")] - //[FieldOffset(32)] - public float cross_track_error; + public byte angleofattack_valid; - /// Deepstall stage. DEEPSTALL_STAGE + /// Sideslip angle measurement valid [Units("")] - [Description("Deepstall stage.")] - //[FieldOffset(36)] - public /*DEEPSTALL_STAGE*/byte stage; + [Description("Sideslip angle measurement valid")] + //[FieldOffset(17)] + public byte sideslip_valid; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// 3 axis gimbal measurements. - public struct mavlink_gimbal_report_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)] + /// The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + public struct mavlink_sys_status_t { /// packet ordered constructor - public mavlink_gimbal_report_t(float delta_time,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_el,float joint_az,byte target_system,byte target_component) + public mavlink_sys_status_t(/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_present,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_enabled,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_health,ushort load,ushort voltage_battery,short current_battery,ushort drop_rate_comm,ushort errors_comm,ushort errors_count1,ushort errors_count2,ushort errors_count3,ushort errors_count4,sbyte battery_remaining) { - this.delta_time = delta_time; - this.delta_angle_x = delta_angle_x; - this.delta_angle_y = delta_angle_y; - this.delta_angle_z = delta_angle_z; - this.delta_velocity_x = delta_velocity_x; - this.delta_velocity_y = delta_velocity_y; - this.delta_velocity_z = delta_velocity_z; - this.joint_roll = joint_roll; - this.joint_el = joint_el; - this.joint_az = joint_az; - this.target_system = target_system; - this.target_component = target_component; + this.onboard_control_sensors_present = onboard_control_sensors_present; + this.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + this.onboard_control_sensors_health = onboard_control_sensors_health; + this.load = load; + this.voltage_battery = voltage_battery; + this.current_battery = current_battery; + this.drop_rate_comm = drop_rate_comm; + this.errors_comm = errors_comm; + this.errors_count1 = errors_count1; + this.errors_count2 = errors_count2; + this.errors_count3 = errors_count3; + this.errors_count4 = errors_count4; + this.battery_remaining = battery_remaining; } /// packet xml order - public static mavlink_gimbal_report_t PopulateXMLOrder(byte target_system,byte target_component,float delta_time,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_el,float joint_az) + public static mavlink_sys_status_t PopulateXMLOrder(/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_present,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_enabled,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_health,ushort load,ushort voltage_battery,short current_battery,sbyte battery_remaining,ushort drop_rate_comm,ushort errors_comm,ushort errors_count1,ushort errors_count2,ushort errors_count3,ushort errors_count4) { - var msg = new mavlink_gimbal_report_t(); + var msg = new mavlink_sys_status_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.delta_time = delta_time; - msg.delta_angle_x = delta_angle_x; - msg.delta_angle_y = delta_angle_y; - msg.delta_angle_z = delta_angle_z; - msg.delta_velocity_x = delta_velocity_x; - msg.delta_velocity_y = delta_velocity_y; - msg.delta_velocity_z = delta_velocity_z; - msg.joint_roll = joint_roll; - msg.joint_el = joint_el; - msg.joint_az = joint_az; + msg.onboard_control_sensors_present = onboard_control_sensors_present; + msg.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + msg.onboard_control_sensors_health = onboard_control_sensors_health; + msg.load = load; + msg.voltage_battery = voltage_battery; + msg.current_battery = current_battery; + msg.battery_remaining = battery_remaining; + msg.drop_rate_comm = drop_rate_comm; + msg.errors_comm = errors_comm; + msg.errors_count1 = errors_count1; + msg.errors_count2 = errors_count2; + msg.errors_count3 = errors_count3; + msg.errors_count4 = errors_count4; return msg; } - /// Time since last update. [s] - [Units("[s]")] - [Description("Time since last update.")] + /// Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. MAV_SYS_STATUS_SENSOR bitmask + [Units("")] + [Description("Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.")] //[FieldOffset(0)] - public float delta_time; + public /*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_present; - /// Delta angle X. [rad] - [Units("[rad]")] - [Description("Delta angle X.")] + /// Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. MAV_SYS_STATUS_SENSOR bitmask + [Units("")] + [Description("Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.")] //[FieldOffset(4)] - public float delta_angle_x; + public /*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_enabled; - /// Delta angle Y. [rad] - [Units("[rad]")] - [Description("Delta angle Y.")] + /// Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. MAV_SYS_STATUS_SENSOR bitmask + [Units("")] + [Description("Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.")] //[FieldOffset(8)] - public float delta_angle_y; + public /*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_health; - /// Delta angle X. [rad] - [Units("[rad]")] - [Description("Delta angle X.")] + /// Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 [d%] + [Units("[d%]")] + [Description("Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000")] //[FieldOffset(12)] - public float delta_angle_z; + public ushort load; - /// Delta velocity X. [m/s] - [Units("[m/s]")] - [Description("Delta velocity X.")] - //[FieldOffset(16)] - public float delta_velocity_x; + /// Battery voltage, UINT16_MAX: Voltage not sent by autopilot [mV] + [Units("[mV]")] + [Description("Battery voltage, UINT16_MAX: Voltage not sent by autopilot")] + //[FieldOffset(14)] + public ushort voltage_battery; - /// Delta velocity Y. [m/s] - [Units("[m/s]")] - [Description("Delta velocity Y.")] - //[FieldOffset(20)] - public float delta_velocity_y; + /// Battery current, -1: Current not sent by autopilot [cA] + [Units("[cA]")] + [Description("Battery current, -1: Current not sent by autopilot")] + //[FieldOffset(16)] + public short current_battery; - /// Delta velocity Z. [m/s] - [Units("[m/s]")] - [Description("Delta velocity Z.")] - //[FieldOffset(24)] - public float delta_velocity_z; + /// Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) [c%] + [Units("[c%]")] + [Description("Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)")] + //[FieldOffset(18)] + public ushort drop_rate_comm; - /// Joint ROLL. [rad] - [Units("[rad]")] - [Description("Joint ROLL.")] - //[FieldOffset(28)] - public float joint_roll; + /// Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + [Units("")] + [Description("Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)")] + //[FieldOffset(20)] + public ushort errors_comm; - /// Joint EL. [rad] - [Units("[rad]")] - [Description("Joint EL.")] - //[FieldOffset(32)] - public float joint_el; + /// Autopilot-specific errors + [Units("")] + [Description("Autopilot-specific errors")] + //[FieldOffset(22)] + public ushort errors_count1; - /// Joint AZ. [rad] - [Units("[rad]")] - [Description("Joint AZ.")] - //[FieldOffset(36)] - public float joint_az; + /// Autopilot-specific errors + [Units("")] + [Description("Autopilot-specific errors")] + //[FieldOffset(24)] + public ushort errors_count2; - /// System ID. + /// Autopilot-specific errors [Units("")] - [Description("System ID.")] - //[FieldOffset(40)] - public byte target_system; + [Description("Autopilot-specific errors")] + //[FieldOffset(26)] + public ushort errors_count3; - /// Component ID. + /// Autopilot-specific errors [Units("")] - [Description("Component ID.")] - //[FieldOffset(41)] - public byte target_component; + [Description("Autopilot-specific errors")] + //[FieldOffset(28)] + public ushort errors_count4; + + /// Battery energy remaining, -1: Battery remaining energy not sent by autopilot [%] + [Units("[%]")] + [Description("Battery energy remaining, -1: Battery remaining energy not sent by autopilot")] + //[FieldOffset(30)] + public sbyte battery_remaining; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - /// Control message for rate gimbal. - public struct mavlink_gimbal_control_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// The system time is the time of the master clock, typically the computer clock of the main onboard computer. + public struct mavlink_system_time_t { /// packet ordered constructor - public mavlink_gimbal_control_t(float demanded_rate_x,float demanded_rate_y,float demanded_rate_z,byte target_system,byte target_component) + public mavlink_system_time_t(ulong time_unix_usec,uint time_boot_ms) { - this.demanded_rate_x = demanded_rate_x; - this.demanded_rate_y = demanded_rate_y; - this.demanded_rate_z = demanded_rate_z; - this.target_system = target_system; - this.target_component = target_component; + this.time_unix_usec = time_unix_usec; + this.time_boot_ms = time_boot_ms; } /// packet xml order - public static mavlink_gimbal_control_t PopulateXMLOrder(byte target_system,byte target_component,float demanded_rate_x,float demanded_rate_y,float demanded_rate_z) + public static mavlink_system_time_t PopulateXMLOrder(ulong time_unix_usec,uint time_boot_ms) { - var msg = new mavlink_gimbal_control_t(); + var msg = new mavlink_system_time_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.demanded_rate_x = demanded_rate_x; - msg.demanded_rate_y = demanded_rate_y; - msg.demanded_rate_z = demanded_rate_z; + msg.time_unix_usec = time_unix_usec; + msg.time_boot_ms = time_boot_ms; return msg; } - /// Demanded angular rate X. [rad/s] - [Units("[rad/s]")] - [Description("Demanded angular rate X.")] + /// Timestamp (UNIX epoch time). [us] + [Units("[us]")] + [Description("Timestamp (UNIX epoch time).")] //[FieldOffset(0)] - public float demanded_rate_x; - - /// Demanded angular rate Y. [rad/s] - [Units("[rad/s]")] - [Description("Demanded angular rate Y.")] - //[FieldOffset(4)] - public float demanded_rate_y; + public ulong time_unix_usec; - /// Demanded angular rate Z. [rad/s] - [Units("[rad/s]")] - [Description("Demanded angular rate Z.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(8)] - public float demanded_rate_z; - - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(12)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(13)] - public byte target_component; + public uint time_boot_ms; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// 100 Hz gimbal torque command telemetry. - public struct mavlink_gimbal_torque_cmd_report_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html + public struct mavlink_ping_t { /// packet ordered constructor - public mavlink_gimbal_torque_cmd_report_t(short rl_torque_cmd,short el_torque_cmd,short az_torque_cmd,byte target_system,byte target_component) + public mavlink_ping_t(ulong time_usec,uint seq,byte target_system,byte target_component) { - this.rl_torque_cmd = rl_torque_cmd; - this.el_torque_cmd = el_torque_cmd; - this.az_torque_cmd = az_torque_cmd; + this.time_usec = time_usec; + this.seq = seq; this.target_system = target_system; this.target_component = target_component; } /// packet xml order - public static mavlink_gimbal_torque_cmd_report_t PopulateXMLOrder(byte target_system,byte target_component,short rl_torque_cmd,short el_torque_cmd,short az_torque_cmd) + public static mavlink_ping_t PopulateXMLOrder(ulong time_usec,uint seq,byte target_system,byte target_component) { - var msg = new mavlink_gimbal_torque_cmd_report_t(); + var msg = new mavlink_ping_t(); + msg.time_usec = time_usec; + msg.seq = seq; msg.target_system = target_system; msg.target_component = target_component; - msg.rl_torque_cmd = rl_torque_cmd; - msg.el_torque_cmd = el_torque_cmd; - msg.az_torque_cmd = az_torque_cmd; return msg; } - /// Roll Torque Command. - [Units("")] - [Description("Roll Torque Command.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public short rl_torque_cmd; - - /// Elevation Torque Command. - [Units("")] - [Description("Elevation Torque Command.")] - //[FieldOffset(2)] - public short el_torque_cmd; + public ulong time_usec; - /// Azimuth Torque Command. + /// PING sequence [Units("")] - [Description("Azimuth Torque Command.")] - //[FieldOffset(4)] - public short az_torque_cmd; + [Description("PING sequence")] + //[FieldOffset(8)] + public uint seq; - /// System ID. + /// 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system [Units("")] - [Description("System ID.")] - //[FieldOffset(6)] + [Description("0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system")] + //[FieldOffset(12)] public byte target_system; - /// Component ID. + /// 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. [Units("")] - [Description("Component ID.")] - //[FieldOffset(7)] + [Description("0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.")] + //[FieldOffset(13)] public byte target_component; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Heartbeat from a HeroBus attached GoPro. - public struct mavlink_gopro_heartbeat_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// Request to control this MAV + public struct mavlink_change_operator_control_t { /// packet ordered constructor - public mavlink_gopro_heartbeat_t(/*GOPRO_HEARTBEAT_STATUS*/byte status,/*GOPRO_CAPTURE_MODE*/byte capture_mode,/*GOPRO_HEARTBEAT_FLAGS*/byte flags) + public mavlink_change_operator_control_t(byte target_system,byte control_request,byte version,byte[] passkey) { - this.status = status; - this.capture_mode = capture_mode; - this.flags = flags; + this.target_system = target_system; + this.control_request = control_request; + this.version = version; + this.passkey = passkey; } /// packet xml order - public static mavlink_gopro_heartbeat_t PopulateXMLOrder(/*GOPRO_HEARTBEAT_STATUS*/byte status,/*GOPRO_CAPTURE_MODE*/byte capture_mode,/*GOPRO_HEARTBEAT_FLAGS*/byte flags) + public static mavlink_change_operator_control_t PopulateXMLOrder(byte target_system,byte control_request,byte version,byte[] passkey) { - var msg = new mavlink_gopro_heartbeat_t(); + var msg = new mavlink_change_operator_control_t(); - msg.status = status; - msg.capture_mode = capture_mode; - msg.flags = flags; + msg.target_system = target_system; + msg.control_request = control_request; + msg.version = version; + msg.passkey = passkey; return msg; } - /// Status. GOPRO_HEARTBEAT_STATUS + /// System the GCS requests control for [Units("")] - [Description("Status.")] + [Description("System the GCS requests control for")] //[FieldOffset(0)] - public /*GOPRO_HEARTBEAT_STATUS*/byte status; + public byte target_system; - /// Current capture mode. GOPRO_CAPTURE_MODE + /// 0: request control of this MAV, 1: Release control of this MAV [Units("")] - [Description("Current capture mode.")] + [Description("0: request control of this MAV, 1: Release control of this MAV")] //[FieldOffset(1)] - public /*GOPRO_CAPTURE_MODE*/byte capture_mode; + public byte control_request; - /// Additional status bits. GOPRO_HEARTBEAT_FLAGS bitmask - [Units("")] - [Description("Additional status bits.")] + /// 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. [rad] + [Units("[rad]")] + [Description("0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.")] //[FieldOffset(2)] - public /*GOPRO_HEARTBEAT_FLAGS*/byte flags; + public byte version; + + /// Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and '!?,.-' + [Units("")] + [Description("Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and '!?,.-'")] + //[FieldOffset(3)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=25)] + public byte[] passkey; }; /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Request a GOPRO_COMMAND response from the GoPro. - public struct mavlink_gopro_get_request_t + /// Accept / deny control of this MAV + public struct mavlink_change_operator_control_ack_t { /// packet ordered constructor - public mavlink_gopro_get_request_t(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id) + public mavlink_change_operator_control_ack_t(byte gcs_system_id,byte control_request,byte ack) { - this.target_system = target_system; - this.target_component = target_component; - this.cmd_id = cmd_id; + this.gcs_system_id = gcs_system_id; + this.control_request = control_request; + this.ack = ack; } /// packet xml order - public static mavlink_gopro_get_request_t PopulateXMLOrder(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id) + public static mavlink_change_operator_control_ack_t PopulateXMLOrder(byte gcs_system_id,byte control_request,byte ack) { - var msg = new mavlink_gopro_get_request_t(); + var msg = new mavlink_change_operator_control_ack_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.cmd_id = cmd_id; + msg.gcs_system_id = gcs_system_id; + msg.control_request = control_request; + msg.ack = ack; return msg; } - /// System ID. + /// ID of the GCS this message [Units("")] - [Description("System ID.")] + [Description("ID of the GCS this message ")] //[FieldOffset(0)] - public byte target_system; + public byte gcs_system_id; - /// Component ID. + /// 0: request control of this MAV, 1: Release control of this MAV [Units("")] - [Description("Component ID.")] + [Description("0: request control of this MAV, 1: Release control of this MAV")] //[FieldOffset(1)] - public byte target_component; + public byte control_request; - /// Command ID. GOPRO_COMMAND + /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control [Units("")] - [Description("Command ID.")] + [Description("0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control")] //[FieldOffset(2)] - public /*GOPRO_COMMAND*/byte cmd_id; + public byte ack; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Response from a GOPRO_COMMAND get request. - public struct mavlink_gopro_get_response_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] + /// Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + public struct mavlink_auth_key_t { /// packet ordered constructor - public mavlink_gopro_get_response_t(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status,byte[] value) + public mavlink_auth_key_t(byte[] key) { - this.cmd_id = cmd_id; - this.status = status; - this.value = value; + this.key = key; } /// packet xml order - public static mavlink_gopro_get_response_t PopulateXMLOrder(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status,byte[] value) + public static mavlink_auth_key_t PopulateXMLOrder(byte[] key) { - var msg = new mavlink_gopro_get_response_t(); + var msg = new mavlink_auth_key_t(); - msg.cmd_id = cmd_id; - msg.status = status; - msg.value = value; + msg.key = key; return msg; } - /// Command ID. GOPRO_COMMAND + /// key [Units("")] - [Description("Command ID.")] + [Description("key")] //[FieldOffset(0)] - public /*GOPRO_COMMAND*/byte cmd_id; - - /// Status. GOPRO_REQUEST_STATUS - [Units("")] - [Description("Status.")] - //[FieldOffset(1)] - public /*GOPRO_REQUEST_STATUS*/byte status; - - /// Value. - [Units("")] - [Description("Value.")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] value; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] key; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] - /// Request to set a GOPRO_COMMAND with a desired. - public struct mavlink_gopro_set_request_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + public struct mavlink_set_mode_t { /// packet ordered constructor - public mavlink_gopro_set_request_t(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id,byte[] value) + public mavlink_set_mode_t(uint custom_mode,byte target_system,/*MAV_MODE*/byte base_mode) { + this.custom_mode = custom_mode; this.target_system = target_system; - this.target_component = target_component; - this.cmd_id = cmd_id; - this.value = value; + this.base_mode = base_mode; } /// packet xml order - public static mavlink_gopro_set_request_t PopulateXMLOrder(byte target_system,byte target_component,/*GOPRO_COMMAND*/byte cmd_id,byte[] value) + public static mavlink_set_mode_t PopulateXMLOrder(byte target_system,/*MAV_MODE*/byte base_mode,uint custom_mode) { - var msg = new mavlink_gopro_set_request_t(); + var msg = new mavlink_set_mode_t(); msg.target_system = target_system; - msg.target_component = target_component; - msg.cmd_id = cmd_id; - msg.value = value; + msg.base_mode = base_mode; + msg.custom_mode = custom_mode; return msg; } - /// System ID. + /// The new autopilot-specific mode. This field can be ignored by an autopilot. [Units("")] - [Description("System ID.")] + [Description("The new autopilot-specific mode. This field can be ignored by an autopilot.")] //[FieldOffset(0)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(1)] - public byte target_component; + public uint custom_mode; - /// Command ID. GOPRO_COMMAND + /// The system setting the mode [Units("")] - [Description("Command ID.")] - //[FieldOffset(2)] - public /*GOPRO_COMMAND*/byte cmd_id; + [Description("The system setting the mode")] + //[FieldOffset(4)] + public byte target_system; - /// Value. + /// The new base mode. MAV_MODE [Units("")] - [Description("Value.")] - //[FieldOffset(3)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] value; + [Description("The new base mode.")] + //[FieldOffset(5)] + public /*MAV_MODE*/byte base_mode; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Response from a GOPRO_COMMAND set request. - public struct mavlink_gopro_set_response_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code. + public struct mavlink_param_request_read_t { /// packet ordered constructor - public mavlink_gopro_set_response_t(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status) + public mavlink_param_request_read_t(short param_index,byte target_system,byte target_component,byte[] param_id) { - this.cmd_id = cmd_id; - this.status = status; + this.param_index = param_index; + this.target_system = target_system; + this.target_component = target_component; + this.param_id = param_id; } /// packet xml order - public static mavlink_gopro_set_response_t PopulateXMLOrder(/*GOPRO_COMMAND*/byte cmd_id,/*GOPRO_REQUEST_STATUS*/byte status) + public static mavlink_param_request_read_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,short param_index) { - var msg = new mavlink_gopro_set_response_t(); + var msg = new mavlink_param_request_read_t(); - msg.cmd_id = cmd_id; - msg.status = status; + msg.target_system = target_system; + msg.target_component = target_component; + msg.param_id = param_id; + msg.param_index = param_index; return msg; } - /// Command ID. GOPRO_COMMAND + /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) [Units("")] - [Description("Command ID.")] + [Description("Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)")] //[FieldOffset(0)] - public /*GOPRO_COMMAND*/byte cmd_id; + public short param_index; - /// Status. GOPRO_REQUEST_STATUS + /// System ID [Units("")] - [Description("Status.")] - //[FieldOffset(1)] - public /*GOPRO_REQUEST_STATUS*/byte status; + [Description("System ID")] + //[FieldOffset(2)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(3)] + public byte target_component; + + /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + [Units("")] + [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// RPM sensor output. - public struct mavlink_rpm_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html + public struct mavlink_param_request_list_t { /// packet ordered constructor - public mavlink_rpm_t(float rpm1,float rpm2) + public mavlink_param_request_list_t(byte target_system,byte target_component) { - this.rpm1 = rpm1; - this.rpm2 = rpm2; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_rpm_t PopulateXMLOrder(float rpm1,float rpm2) + public static mavlink_param_request_list_t PopulateXMLOrder(byte target_system,byte target_component) { - var msg = new mavlink_rpm_t(); + var msg = new mavlink_param_request_list_t(); - msg.rpm1 = rpm1; - msg.rpm2 = rpm2; + msg.target_system = target_system; + msg.target_component = target_component; return msg; } - /// RPM Sensor1. + /// System ID [Units("")] - [Description("RPM Sensor1.")] + [Description("System ID")] //[FieldOffset(0)] - public float rpm1; + public byte target_system; - /// RPM Sensor2. + /// Component ID [Units("")] - [Description("RPM Sensor2.")] - //[FieldOffset(4)] - public float rpm2; + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; }; - /// extensions_start 9 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] - /// Read registers for a device. - public struct mavlink_device_op_read_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)] + /// Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html + public struct mavlink_param_value_t { /// packet ordered constructor - public mavlink_device_op_read_t(uint request_id,byte target_system,byte target_component,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte bank) + public mavlink_param_value_t(float param_value,ushort param_count,ushort param_index,byte[] param_id,/*MAV_PARAM_TYPE*/byte param_type) { - this.request_id = request_id; - this.target_system = target_system; - this.target_component = target_component; - this.bustype = bustype; - this.bus = bus; - this.address = address; - this.busname = busname; - this.regstart = regstart; - this.count = count; - this.bank = bank; + this.param_value = param_value; + this.param_count = param_count; + this.param_index = param_index; + this.param_id = param_id; + this.param_type = param_type; } /// packet xml order - public static mavlink_device_op_read_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte bank) + public static mavlink_param_value_t PopulateXMLOrder(byte[] param_id,float param_value,/*MAV_PARAM_TYPE*/byte param_type,ushort param_count,ushort param_index) { - var msg = new mavlink_device_op_read_t(); + var msg = new mavlink_param_value_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.request_id = request_id; - msg.bustype = bustype; - msg.bus = bus; - msg.address = address; - msg.busname = busname; - msg.regstart = regstart; - msg.count = count; - msg.bank = bank; + msg.param_id = param_id; + msg.param_value = param_value; + msg.param_type = param_type; + msg.param_count = param_count; + msg.param_index = param_index; return msg; } - /// Request ID - copied to reply. + /// Onboard parameter value [Units("")] - [Description("Request ID - copied to reply.")] + [Description("Onboard parameter value")] //[FieldOffset(0)] - public uint request_id; + public float param_value; - /// System ID. + /// Total number of onboard parameters [Units("")] - [Description("System ID.")] + [Description("Total number of onboard parameters")] //[FieldOffset(4)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + public ushort param_count; - /// The bus type. DEVICE_OP_BUSTYPE + /// Index of this onboard parameter [Units("")] - [Description("The bus type.")] + [Description("Index of this onboard parameter")] //[FieldOffset(6)] - public /*DEVICE_OP_BUSTYPE*/byte bustype; - - /// Bus number. - [Units("")] - [Description("Bus number.")] - //[FieldOffset(7)] - public byte bus; + public ushort param_index; - /// Bus address. + /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string [Units("")] - [Description("Bus address.")] + [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] //[FieldOffset(8)] - public byte address; - - /// Name of device on bus (for SPI). - [Units("")] - [Description("Name of device on bus (for SPI).")] - //[FieldOffset(9)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=40)] - public byte[] busname; - - /// First register to read. - [Units("")] - [Description("First register to read.")] - //[FieldOffset(49)] - public byte regstart; - - /// Count of registers to read. - [Units("")] - [Description("Count of registers to read.")] - //[FieldOffset(50)] - public byte count; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; - /// Bank number. + /// Onboard parameter type. MAV_PARAM_TYPE [Units("")] - [Description("Bank number.")] - //[FieldOffset(51)] - public byte bank; + [Description("Onboard parameter type.")] + //[FieldOffset(24)] + public /*MAV_PARAM_TYPE*/byte param_type; }; - /// extensions_start 5 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=136)] - /// Read registers reply. - public struct mavlink_device_op_read_reply_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] + /// Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. + public struct mavlink_param_set_t { /// packet ordered constructor - public mavlink_device_op_read_reply_t(uint request_id,byte result,byte regstart,byte count,byte[] data,byte bank) + public mavlink_param_set_t(float param_value,byte target_system,byte target_component,byte[] param_id,/*MAV_PARAM_TYPE*/byte param_type) { - this.request_id = request_id; - this.result = result; - this.regstart = regstart; - this.count = count; - this.data = data; - this.bank = bank; + this.param_value = param_value; + this.target_system = target_system; + this.target_component = target_component; + this.param_id = param_id; + this.param_type = param_type; } /// packet xml order - public static mavlink_device_op_read_reply_t PopulateXMLOrder(uint request_id,byte result,byte regstart,byte count,byte[] data,byte bank) + public static mavlink_param_set_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,float param_value,/*MAV_PARAM_TYPE*/byte param_type) { - var msg = new mavlink_device_op_read_reply_t(); + var msg = new mavlink_param_set_t(); - msg.request_id = request_id; - msg.result = result; - msg.regstart = regstart; - msg.count = count; - msg.data = data; - msg.bank = bank; + msg.target_system = target_system; + msg.target_component = target_component; + msg.param_id = param_id; + msg.param_value = param_value; + msg.param_type = param_type; return msg; } - /// Request ID - copied from request. + /// Onboard parameter value [Units("")] - [Description("Request ID - copied from request.")] + [Description("Onboard parameter value")] //[FieldOffset(0)] - public uint request_id; + public float param_value; - /// 0 for success, anything else is failure code. + /// System ID [Units("")] - [Description("0 for success, anything else is failure code.")] + [Description("System ID")] //[FieldOffset(4)] - public byte result; + public byte target_system; - /// Starting register. + /// Component ID [Units("")] - [Description("Starting register.")] + [Description("Component ID")] //[FieldOffset(5)] - public byte regstart; + public byte target_component; - /// Count of bytes read. + /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string [Units("")] - [Description("Count of bytes read.")] + [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] //[FieldOffset(6)] - public byte count; - - /// Reply data. - [Units("")] - [Description("Reply data.")] - //[FieldOffset(7)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] - public byte[] data; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; - /// Bank number. + /// Onboard parameter type. MAV_PARAM_TYPE [Units("")] - [Description("Bank number.")] - //[FieldOffset(135)] - public byte bank; + [Description("Onboard parameter type.")] + //[FieldOffset(22)] + public /*MAV_PARAM_TYPE*/byte param_type; }; /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=180)] - /// Write registers for a device. - public struct mavlink_device_op_write_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] + /// The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. + public struct mavlink_gps_raw_int_t { /// packet ordered constructor - public mavlink_device_op_write_t(uint request_id,byte target_system,byte target_component,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte[] data,byte bank) + public mavlink_gps_raw_int_t(ulong time_usec,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,/*GPS_FIX_TYPE*/byte fix_type,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw) { - this.request_id = request_id; - this.target_system = target_system; - this.target_component = target_component; - this.bustype = bustype; - this.bus = bus; - this.address = address; - this.busname = busname; - this.regstart = regstart; - this.count = count; - this.data = data; - this.bank = bank; + this.time_usec = time_usec; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.eph = eph; + this.epv = epv; + this.vel = vel; + this.cog = cog; + this.fix_type = fix_type; + this.satellites_visible = satellites_visible; + this.alt_ellipsoid = alt_ellipsoid; + this.h_acc = h_acc; + this.v_acc = v_acc; + this.vel_acc = vel_acc; + this.hdg_acc = hdg_acc; + this.yaw = yaw; } /// packet xml order - public static mavlink_device_op_write_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,/*DEVICE_OP_BUSTYPE*/byte bustype,byte bus,byte address,byte[] busname,byte regstart,byte count,byte[] data,byte bank) + public static mavlink_gps_raw_int_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_TYPE*/byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw) { - var msg = new mavlink_device_op_write_t(); + var msg = new mavlink_gps_raw_int_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.request_id = request_id; - msg.bustype = bustype; - msg.bus = bus; - msg.address = address; - msg.busname = busname; - msg.regstart = regstart; - msg.count = count; - msg.data = data; - msg.bank = bank; + msg.time_usec = time_usec; + msg.fix_type = fix_type; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.eph = eph; + msg.epv = epv; + msg.vel = vel; + msg.cog = cog; + msg.satellites_visible = satellites_visible; + msg.alt_ellipsoid = alt_ellipsoid; + msg.h_acc = h_acc; + msg.v_acc = v_acc; + msg.vel_acc = vel_acc; + msg.hdg_acc = hdg_acc; + msg.yaw = yaw; return msg; } - /// Request ID - copied to reply. - [Units("")] - [Description("Request ID - copied to reply.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint request_id; + public ulong time_usec; - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(4)] - public byte target_system; + /// Latitude (WGS84, EGM96 ellipsoid) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84, EGM96 ellipsoid)")] + //[FieldOffset(8)] + public int lat; - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + /// Longitude (WGS84, EGM96 ellipsoid) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84, EGM96 ellipsoid)")] + //[FieldOffset(12)] + public int lon; - /// The bus type. DEVICE_OP_BUSTYPE - [Units("")] - [Description("The bus type.")] - //[FieldOffset(6)] - public /*DEVICE_OP_BUSTYPE*/byte bustype; + /// Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.")] + //[FieldOffset(16)] + public int alt; - /// Bus number. + /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX [Units("")] - [Description("Bus number.")] - //[FieldOffset(7)] - public byte bus; + [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] + //[FieldOffset(20)] + public ushort eph; - /// Bus address. + /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX [Units("")] - [Description("Bus address.")] - //[FieldOffset(8)] - public byte address; + [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + //[FieldOffset(22)] + public ushort epv; - /// Name of device on bus (for SPI). - [Units("")] - [Description("Name of device on bus (for SPI).")] - //[FieldOffset(9)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=40)] - public byte[] busname; + /// GPS ground speed. If unknown, set to: UINT16_MAX [cm/s] + [Units("[cm/s]")] + [Description("GPS ground speed. If unknown, set to: UINT16_MAX")] + //[FieldOffset(24)] + public ushort vel; - /// First register to write. - [Units("")] - [Description("First register to write.")] - //[FieldOffset(49)] - public byte regstart; + /// Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX [cdeg] + [Units("[cdeg]")] + [Description("Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX")] + //[FieldOffset(26)] + public ushort cog; - /// Count of registers to write. + /// GPS fix type. GPS_FIX_TYPE [Units("")] - [Description("Count of registers to write.")] - //[FieldOffset(50)] - public byte count; + [Description("GPS fix type.")] + //[FieldOffset(28)] + public /*GPS_FIX_TYPE*/byte fix_type; - /// Write data. + /// Number of satellites visible. If unknown, set to 255 [Units("")] - [Description("Write data.")] - //[FieldOffset(51)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] - public byte[] data; + [Description("Number of satellites visible. If unknown, set to 255")] + //[FieldOffset(29)] + public byte satellites_visible; - /// Bank number. - [Units("")] - [Description("Bank number.")] - //[FieldOffset(179)] - public byte bank; + /// Altitude (above WGS84, EGM96 ellipsoid). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (above WGS84, EGM96 ellipsoid). Positive for up.")] + //[FieldOffset(30)] + public int alt_ellipsoid; + + /// Position uncertainty. [mm] + [Units("[mm]")] + [Description("Position uncertainty.")] + //[FieldOffset(34)] + public uint h_acc; + + /// Altitude uncertainty. [mm] + [Units("[mm]")] + [Description("Altitude uncertainty.")] + //[FieldOffset(38)] + public uint v_acc; + + /// Speed uncertainty. [mm] + [Units("[mm]")] + [Description("Speed uncertainty.")] + //[FieldOffset(42)] + public uint vel_acc; + + /// Heading / track uncertainty [degE5] + [Units("[degE5]")] + [Description("Heading / track uncertainty")] + //[FieldOffset(46)] + public uint hdg_acc; + + /// Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. [cdeg] + [Units("[cdeg]")] + [Description("Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.")] + //[FieldOffset(50)] + public ushort yaw; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// Write registers reply. - public struct mavlink_device_op_write_reply_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=101)] + /// The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + public struct mavlink_gps_status_t { /// packet ordered constructor - public mavlink_device_op_write_reply_t(uint request_id,byte result) + public mavlink_gps_status_t(byte satellites_visible,byte[] satellite_prn,byte[] satellite_used,byte[] satellite_elevation,byte[] satellite_azimuth,byte[] satellite_snr) { - this.request_id = request_id; - this.result = result; + this.satellites_visible = satellites_visible; + this.satellite_prn = satellite_prn; + this.satellite_used = satellite_used; + this.satellite_elevation = satellite_elevation; + this.satellite_azimuth = satellite_azimuth; + this.satellite_snr = satellite_snr; } /// packet xml order - public static mavlink_device_op_write_reply_t PopulateXMLOrder(uint request_id,byte result) + public static mavlink_gps_status_t PopulateXMLOrder(byte satellites_visible,byte[] satellite_prn,byte[] satellite_used,byte[] satellite_elevation,byte[] satellite_azimuth,byte[] satellite_snr) { - var msg = new mavlink_device_op_write_reply_t(); + var msg = new mavlink_gps_status_t(); - msg.request_id = request_id; - msg.result = result; + msg.satellites_visible = satellites_visible; + msg.satellite_prn = satellite_prn; + msg.satellite_used = satellite_used; + msg.satellite_elevation = satellite_elevation; + msg.satellite_azimuth = satellite_azimuth; + msg.satellite_snr = satellite_snr; return msg; } - /// Request ID - copied from request. + /// Number of satellites visible [Units("")] - [Description("Request ID - copied from request.")] + [Description("Number of satellites visible")] //[FieldOffset(0)] - public uint request_id; + public byte satellites_visible; - /// 0 for success, anything else is failure code. + /// Global satellite ID [Units("")] - [Description("0 for success, anything else is failure code.")] - //[FieldOffset(4)] - public byte result; + [Description("Global satellite ID")] + //[FieldOffset(1)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] satellite_prn; + + /// 0: Satellite not used, 1: used for localization + [Units("")] + [Description("0: Satellite not used, 1: used for localization")] + //[FieldOffset(21)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] satellite_used; + + /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite [deg] + [Units("[deg]")] + [Description("Elevation (0: right on top of receiver, 90: on the horizon) of satellite")] + //[FieldOffset(41)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] satellite_elevation; + + /// Direction of satellite, 0: 0 deg, 255: 360 deg. [deg] + [Units("[deg]")] + [Description("Direction of satellite, 0: 0 deg, 255: 360 deg.")] + //[FieldOffset(61)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] satellite_azimuth; + + /// Signal to noise ratio of satellite [dB] + [Units("[dB]")] + [Description("Signal to noise ratio of satellite")] + //[FieldOffset(81)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] satellite_snr; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=232)] - /// Send a secure command. Data should be signed with a private key corresponding with a public key known to the recipient. Signature should be over the concatenation of the sequence number (little-endian format), the operation (little-endian format) the data and the session key. For SECURE_COMMAND_GET_SESSION_KEY the session key should be zero length. The data array consists of the data followed by the signature. The sum of the data_length and the sig_length cannot be more than 220. The format of the data is command specific. - public struct mavlink_secure_command_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + public struct mavlink_scaled_imu_t { /// packet ordered constructor - public mavlink_secure_command_t(uint sequence,/*SECURE_COMMAND_OP*/uint operation,byte target_system,byte target_component,byte data_length,byte sig_length,byte[] data) + public mavlink_scaled_imu_t(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) { - this.sequence = sequence; - this.operation = operation; - this.target_system = target_system; - this.target_component = target_component; - this.data_length = data_length; - this.sig_length = sig_length; - this.data = data; + this.time_boot_ms = time_boot_ms; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.xmag = xmag; + this.ymag = ymag; + this.zmag = zmag; + this.temperature = temperature; } /// packet xml order - public static mavlink_secure_command_t PopulateXMLOrder(byte target_system,byte target_component,uint sequence,/*SECURE_COMMAND_OP*/uint operation,byte data_length,byte sig_length,byte[] data) + public static mavlink_scaled_imu_t PopulateXMLOrder(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) { - var msg = new mavlink_secure_command_t(); + var msg = new mavlink_scaled_imu_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.sequence = sequence; - msg.operation = operation; - msg.data_length = data_length; - msg.sig_length = sig_length; - msg.data = data; + msg.time_boot_ms = time_boot_ms; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.xmag = xmag; + msg.ymag = ymag; + msg.zmag = zmag; + msg.temperature = temperature; return msg; } - /// Sequence ID for tagging reply. - [Units("")] - [Description("Sequence ID for tagging reply.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public uint sequence; + public uint time_boot_ms; - /// Operation being requested. SECURE_COMMAND_OP - [Units("")] - [Description("Operation being requested.")] + /// X acceleration [mG] + [Units("[mG]")] + [Description("X acceleration")] //[FieldOffset(4)] - public /*SECURE_COMMAND_OP*/uint operation; + public short xacc; - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(8)] - public byte target_system; + /// Y acceleration [mG] + [Units("[mG]")] + [Description("Y acceleration")] + //[FieldOffset(6)] + public short yacc; - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(9)] - public byte target_component; + /// Z acceleration [mG] + [Units("[mG]")] + [Description("Z acceleration")] + //[FieldOffset(8)] + public short zacc; - /// Data length. - [Units("")] - [Description("Data length.")] + /// Angular speed around X axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around X axis")] //[FieldOffset(10)] - public byte data_length; - - /// Signature length. - [Units("")] - [Description("Signature length.")] - //[FieldOffset(11)] - public byte sig_length; + public short xgyro; - /// Signed data. - [Units("")] - [Description("Signed data.")] + /// Angular speed around Y axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around Y axis")] //[FieldOffset(12)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=220)] - public byte[] data; + public short ygyro; + + /// Angular speed around Z axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around Z axis")] + //[FieldOffset(14)] + public short zgyro; + + /// X Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("X Magnetic field")] + //[FieldOffset(16)] + public short xmag; + + /// Y Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("Y Magnetic field")] + //[FieldOffset(18)] + public short ymag; + + /// Z Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("Z Magnetic field")] + //[FieldOffset(20)] + public short zmag; + + /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] + [Units("[cdegC]")] + [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] + //[FieldOffset(22)] + public short temperature; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=230)] - /// Reply from secure command. - public struct mavlink_secure_command_reply_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=29)] + /// The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging. + public struct mavlink_raw_imu_t { /// packet ordered constructor - public mavlink_secure_command_reply_t(uint sequence,/*SECURE_COMMAND_OP*/uint operation,/*MAV_RESULT*/byte result,byte data_length,byte[] data) + public mavlink_raw_imu_t(ulong time_usec,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,byte id,short temperature) { - this.sequence = sequence; - this.operation = operation; - this.result = result; - this.data_length = data_length; - this.data = data; + this.time_usec = time_usec; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.xmag = xmag; + this.ymag = ymag; + this.zmag = zmag; + this.id = id; + this.temperature = temperature; } /// packet xml order - public static mavlink_secure_command_reply_t PopulateXMLOrder(uint sequence,/*SECURE_COMMAND_OP*/uint operation,/*MAV_RESULT*/byte result,byte data_length,byte[] data) + public static mavlink_raw_imu_t PopulateXMLOrder(ulong time_usec,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,byte id,short temperature) { - var msg = new mavlink_secure_command_reply_t(); + var msg = new mavlink_raw_imu_t(); - msg.sequence = sequence; - msg.operation = operation; - msg.result = result; - msg.data_length = data_length; - msg.data = data; + msg.time_usec = time_usec; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.xmag = xmag; + msg.ymag = ymag; + msg.zmag = zmag; + msg.id = id; + msg.temperature = temperature; return msg; } - /// Sequence ID from request. - [Units("")] - [Description("Sequence ID from request.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint sequence; + public ulong time_usec; - /// Operation that was requested. SECURE_COMMAND_OP + /// X acceleration (raw) [Units("")] - [Description("Operation that was requested.")] - //[FieldOffset(4)] - public /*SECURE_COMMAND_OP*/uint operation; + [Description("X acceleration (raw)")] + //[FieldOffset(8)] + public short xacc; - /// Result of command. MAV_RESULT + /// Y acceleration (raw) [Units("")] - [Description("Result of command.")] - //[FieldOffset(8)] - public /*MAV_RESULT*/byte result; + [Description("Y acceleration (raw)")] + //[FieldOffset(10)] + public short yacc; - /// Data length. + /// Z acceleration (raw) [Units("")] - [Description("Data length.")] - //[FieldOffset(9)] - public byte data_length; + [Description("Z acceleration (raw)")] + //[FieldOffset(12)] + public short zacc; - /// Reply data. + /// Angular speed around X axis (raw) [Units("")] - [Description("Reply data.")] - //[FieldOffset(10)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=220)] - public byte[] data; + [Description("Angular speed around X axis (raw)")] + //[FieldOffset(14)] + public short xgyro; + + /// Angular speed around Y axis (raw) + [Units("")] + [Description("Angular speed around Y axis (raw)")] + //[FieldOffset(16)] + public short ygyro; + + /// Angular speed around Z axis (raw) + [Units("")] + [Description("Angular speed around Z axis (raw)")] + //[FieldOffset(18)] + public short zgyro; + + /// X Magnetic field (raw) + [Units("")] + [Description("X Magnetic field (raw)")] + //[FieldOffset(20)] + public short xmag; + + /// Y Magnetic field (raw) + [Units("")] + [Description("Y Magnetic field (raw)")] + //[FieldOffset(22)] + public short ymag; + + /// Z Magnetic field (raw) + [Units("")] + [Description("Z Magnetic field (raw)")] + //[FieldOffset(24)] + public short zmag; + + /// Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) + [Units("")] + [Description("Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)")] + //[FieldOffset(26)] + public byte id; + + /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] + [Units("[cdegC]")] + [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] + //[FieldOffset(27)] + public short temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=49)] - /// Adaptive Controller tuning information. - public struct mavlink_adap_tuning_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + public struct mavlink_raw_pressure_t { /// packet ordered constructor - public mavlink_adap_tuning_t(float desired,float achieved,float error,float theta,float omega,float sigma,float theta_dot,float omega_dot,float sigma_dot,float f,float f_dot,float u,/*PID_TUNING_AXIS*/byte axis) + public mavlink_raw_pressure_t(ulong time_usec,short press_abs,short press_diff1,short press_diff2,short temperature) { - this.desired = desired; - this.achieved = achieved; - this.error = error; - this.theta = theta; - this.omega = omega; - this.sigma = sigma; - this.theta_dot = theta_dot; - this.omega_dot = omega_dot; - this.sigma_dot = sigma_dot; - this.f = f; - this.f_dot = f_dot; - this.u = u; - this.axis = axis; + this.time_usec = time_usec; + this.press_abs = press_abs; + this.press_diff1 = press_diff1; + this.press_diff2 = press_diff2; + this.temperature = temperature; } /// packet xml order - public static mavlink_adap_tuning_t PopulateXMLOrder(/*PID_TUNING_AXIS*/byte axis,float desired,float achieved,float error,float theta,float omega,float sigma,float theta_dot,float omega_dot,float sigma_dot,float f,float f_dot,float u) + public static mavlink_raw_pressure_t PopulateXMLOrder(ulong time_usec,short press_abs,short press_diff1,short press_diff2,short temperature) { - var msg = new mavlink_adap_tuning_t(); + var msg = new mavlink_raw_pressure_t(); - msg.axis = axis; - msg.desired = desired; - msg.achieved = achieved; - msg.error = error; - msg.theta = theta; - msg.omega = omega; - msg.sigma = sigma; - msg.theta_dot = theta_dot; - msg.omega_dot = omega_dot; - msg.sigma_dot = sigma_dot; - msg.f = f; - msg.f_dot = f_dot; - msg.u = u; + msg.time_usec = time_usec; + msg.press_abs = press_abs; + msg.press_diff1 = press_diff1; + msg.press_diff2 = press_diff2; + msg.temperature = temperature; return msg; } - /// Desired rate. [deg/s] - [Units("[deg/s]")] - [Description("Desired rate.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public float desired; - - /// Achieved rate. [deg/s] - [Units("[deg/s]")] - [Description("Achieved rate.")] - //[FieldOffset(4)] - public float achieved; + public ulong time_usec; - /// Error between model and vehicle. + /// Absolute pressure (raw) [Units("")] - [Description("Error between model and vehicle.")] + [Description("Absolute pressure (raw)")] //[FieldOffset(8)] - public float error; - - /// Theta estimated state predictor. - [Units("")] - [Description("Theta estimated state predictor.")] - //[FieldOffset(12)] - public float theta; - - /// Omega estimated state predictor. - [Units("")] - [Description("Omega estimated state predictor.")] - //[FieldOffset(16)] - public float omega; - - /// Sigma estimated state predictor. - [Units("")] - [Description("Sigma estimated state predictor.")] - //[FieldOffset(20)] - public float sigma; - - /// Theta derivative. - [Units("")] - [Description("Theta derivative.")] - //[FieldOffset(24)] - public float theta_dot; - - /// Omega derivative. - [Units("")] - [Description("Omega derivative.")] - //[FieldOffset(28)] - public float omega_dot; - - /// Sigma derivative. - [Units("")] - [Description("Sigma derivative.")] - //[FieldOffset(32)] - public float sigma_dot; - - /// Projection operator value. - [Units("")] - [Description("Projection operator value.")] - //[FieldOffset(36)] - public float f; + public short press_abs; - /// Projection operator derivative. + /// Differential pressure 1 (raw, 0 if nonexistent) [Units("")] - [Description("Projection operator derivative.")] - //[FieldOffset(40)] - public float f_dot; + [Description("Differential pressure 1 (raw, 0 if nonexistent)")] + //[FieldOffset(10)] + public short press_diff1; - /// u adaptive controlled output command. + /// Differential pressure 2 (raw, 0 if nonexistent) [Units("")] - [Description("u adaptive controlled output command.")] - //[FieldOffset(44)] - public float u; + [Description("Differential pressure 2 (raw, 0 if nonexistent)")] + //[FieldOffset(12)] + public short press_diff2; - /// Axis. PID_TUNING_AXIS + /// Raw Temperature measurement (raw) [Units("")] - [Description("Axis.")] - //[FieldOffset(48)] - public /*PID_TUNING_AXIS*/byte axis; + [Description("Raw Temperature measurement (raw)")] + //[FieldOffset(14)] + public short temperature; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// Camera vision based attitude and position deltas. - public struct mavlink_vision_position_delta_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + public struct mavlink_scaled_pressure_t { /// packet ordered constructor - public mavlink_vision_position_delta_t(ulong time_usec,ulong time_delta_usec,float[] angle_delta,float[] position_delta,float confidence) + public mavlink_scaled_pressure_t(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) { - this.time_usec = time_usec; - this.time_delta_usec = time_delta_usec; - this.angle_delta = angle_delta; - this.position_delta = position_delta; - this.confidence = confidence; + this.time_boot_ms = time_boot_ms; + this.press_abs = press_abs; + this.press_diff = press_diff; + this.temperature = temperature; + this.temperature_press_diff = temperature_press_diff; } /// packet xml order - public static mavlink_vision_position_delta_t PopulateXMLOrder(ulong time_usec,ulong time_delta_usec,float[] angle_delta,float[] position_delta,float confidence) + public static mavlink_scaled_pressure_t PopulateXMLOrder(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) { - var msg = new mavlink_vision_position_delta_t(); + var msg = new mavlink_scaled_pressure_t(); - msg.time_usec = time_usec; - msg.time_delta_usec = time_delta_usec; - msg.angle_delta = angle_delta; - msg.position_delta = position_delta; - msg.confidence = confidence; + msg.time_boot_ms = time_boot_ms; + msg.press_abs = press_abs; + msg.press_diff = press_diff; + msg.temperature = temperature; + msg.temperature_press_diff = temperature_press_diff; return msg; } - /// Timestamp (synced to UNIX time or since system boot). [us] - [Units("[us]")] - [Description("Timestamp (synced to UNIX time or since system boot).")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// Time since the last reported camera frame. [us] - [Units("[us]")] - [Description("Time since the last reported camera frame.")] - //[FieldOffset(8)] - public ulong time_delta_usec; + /// Absolute pressure [hPa] + [Units("[hPa]")] + [Description("Absolute pressure")] + //[FieldOffset(4)] + public float press_abs; - /// Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD. [rad] - [Units("[rad]")] - [Description("Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] angle_delta; + /// Differential pressure 1 [hPa] + [Units("[hPa]")] + [Description("Differential pressure 1")] + //[FieldOffset(8)] + public float press_diff; - /// Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD. [m] - [Units("[m]")] - [Description("Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.")] - //[FieldOffset(28)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] position_delta; + /// Absolute pressure temperature [cdegC] + [Units("[cdegC]")] + [Description("Absolute pressure temperature")] + //[FieldOffset(12)] + public short temperature; - /// Normalised confidence value from 0 to 100. [%] - [Units("[%]")] - [Description("Normalised confidence value from 0 to 100.")] - //[FieldOffset(40)] - public float confidence; + /// Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. [cdegC] + [Units("[cdegC]")] + [Description("Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.")] + //[FieldOffset(14)] + public short temperature_press_diff; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// Angle of Attack and Side Slip Angle. - public struct mavlink_aoa_ssa_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + public struct mavlink_attitude_t { /// packet ordered constructor - public mavlink_aoa_ssa_t(ulong time_usec,float AOA,float SSA) + public mavlink_attitude_t(uint time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) { - this.time_usec = time_usec; - this.AOA = AOA; - this.SSA = SSA; + this.time_boot_ms = time_boot_ms; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.rollspeed = rollspeed; + this.pitchspeed = pitchspeed; + this.yawspeed = yawspeed; } /// packet xml order - public static mavlink_aoa_ssa_t PopulateXMLOrder(ulong time_usec,float AOA,float SSA) + public static mavlink_attitude_t PopulateXMLOrder(uint time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) { - var msg = new mavlink_aoa_ssa_t(); + var msg = new mavlink_attitude_t(); - msg.time_usec = time_usec; - msg.AOA = AOA; - msg.SSA = SSA; + msg.time_boot_ms = time_boot_ms; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.rollspeed = rollspeed; + msg.pitchspeed = pitchspeed; + msg.yawspeed = yawspeed; return msg; } - /// Timestamp (since boot or Unix epoch). [us] - [Units("[us]")] - [Description("Timestamp (since boot or Unix epoch).")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// Angle of Attack. [deg] - [Units("[deg]")] - [Description("Angle of Attack.")] + /// Roll angle (-pi..+pi) [rad] + [Units("[rad]")] + [Description("Roll angle (-pi..+pi)")] + //[FieldOffset(4)] + public float roll; + + /// Pitch angle (-pi..+pi) [rad] + [Units("[rad]")] + [Description("Pitch angle (-pi..+pi)")] //[FieldOffset(8)] - public float AOA; + public float pitch; - /// Side Slip Angle. [deg] - [Units("[deg]")] - [Description("Side Slip Angle.")] + /// Yaw angle (-pi..+pi) [rad] + [Units("[rad]")] + [Description("Yaw angle (-pi..+pi)")] //[FieldOffset(12)] - public float SSA; + public float yaw; + + /// Roll angular speed [rad/s] + [Units("[rad/s]")] + [Description("Roll angular speed")] + //[FieldOffset(16)] + public float rollspeed; + + /// Pitch angular speed [rad/s] + [Units("[rad/s]")] + [Description("Pitch angular speed")] + //[FieldOffset(20)] + public float pitchspeed; + + /// Yaw angular speed [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular speed")] + //[FieldOffset(24)] + public float yawspeed; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_1_to_4_t + /// extensions_start 8 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=48)] + /// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + public struct mavlink_attitude_quaternion_t { /// packet ordered constructor - public mavlink_esc_telemetry_1_to_4_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_attitude_quaternion_t(uint time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,float[] repr_offset_q) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.time_boot_ms = time_boot_ms; + this.q1 = q1; + this.q2 = q2; + this.q3 = q3; + this.q4 = q4; + this.rollspeed = rollspeed; + this.pitchspeed = pitchspeed; + this.yawspeed = yawspeed; + this.repr_offset_q = repr_offset_q; } /// packet xml order - public static mavlink_esc_telemetry_1_to_4_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_attitude_quaternion_t PopulateXMLOrder(uint time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,float[] repr_offset_q) { - var msg = new mavlink_esc_telemetry_1_to_4_t(); + var msg = new mavlink_attitude_quaternion_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.time_boot_ms = time_boot_ms; + msg.q1 = q1; + msg.q2 = q2; + msg.q3 = q3; + msg.q4 = q4; + msg.rollspeed = rollspeed; + msg.pitchspeed = pitchspeed; + msg.yawspeed = yawspeed; + msg.repr_offset_q = repr_offset_q; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; + public uint time_boot_ms; - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] + /// Quaternion component 1, w (1 in null-rotation) + [Units("")] + [Description("Quaternion component 1, w (1 in null-rotation)")] + //[FieldOffset(4)] + public float q1; + + /// Quaternion component 2, x (0 in null-rotation) + [Units("")] + [Description("Quaternion component 2, x (0 in null-rotation)")] //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; + public float q2; - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] + /// Quaternion component 3, y (0 in null-rotation) + [Units("")] + [Description("Quaternion component 3, y (0 in null-rotation)")] + //[FieldOffset(12)] + public float q3; + + /// Quaternion component 4, z (0 in null-rotation) + [Units("")] + [Description("Quaternion component 4, z (0 in null-rotation)")] //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; + public float q4; - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] + /// Roll angular speed [rad/s] + [Units("[rad/s]")] + [Description("Roll angular speed")] + //[FieldOffset(20)] + public float rollspeed; + + /// Pitch angular speed [rad/s] + [Units("[rad/s]")] + [Description("Pitch angular speed")] //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + public float pitchspeed; - /// count of telemetry packets received (wraps at 65535). + /// Yaw angular speed [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular speed")] + //[FieldOffset(28)] + public float yawspeed; + + /// Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] + [Description("Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.")] //[FieldOffset(32)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; - - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + public float[] repr_offset_q; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_5_to_8_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + public struct mavlink_local_position_ned_t { /// packet ordered constructor - public mavlink_esc_telemetry_5_to_8_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_local_position_ned_t(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.time_boot_ms = time_boot_ms; + this.x = x; + this.y = y; + this.z = z; + this.vx = vx; + this.vy = vy; + this.vz = vz; } /// packet xml order - public static mavlink_esc_telemetry_5_to_8_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_local_position_ned_t PopulateXMLOrder(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz) { - var msg = new mavlink_esc_telemetry_5_to_8_t(); + var msg = new mavlink_local_position_ned_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.time_boot_ms = time_boot_ms; + msg.x = x; + msg.y = y; + msg.z = z; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; + public uint time_boot_ms; - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] + /// X Position [m] + [Units("[m]")] + [Description("X Position")] + //[FieldOffset(4)] + public float x; + + /// Y Position [m] + [Units("[m]")] + [Description("Y Position")] //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; + public float y; - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; + /// Z Position [m] + [Units("[m]")] + [Description("Z Position")] + //[FieldOffset(12)] + public float z; - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + /// X Speed [m/s] + [Units("[m/s]")] + [Description("X Speed")] + //[FieldOffset(16)] + public float vx; - /// count of telemetry packets received (wraps at 65535). - [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + /// Y Speed [m/s] + [Units("[m/s]")] + [Description("Y Speed")] + //[FieldOffset(20)] + public float vy; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Z Speed [m/s] + [Units("[m/s]")] + [Description("Z Speed")] + //[FieldOffset(24)] + public float vz; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_9_to_12_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. + public struct mavlink_global_position_int_t { /// packet ordered constructor - public mavlink_esc_telemetry_9_to_12_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_global_position_int_t(uint time_boot_ms,int lat,int lon,int alt,int relative_alt,short vx,short vy,short vz,ushort hdg) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.time_boot_ms = time_boot_ms; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.relative_alt = relative_alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.hdg = hdg; } /// packet xml order - public static mavlink_esc_telemetry_9_to_12_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_global_position_int_t PopulateXMLOrder(uint time_boot_ms,int lat,int lon,int alt,int relative_alt,short vx,short vy,short vz,ushort hdg) { - var msg = new mavlink_esc_telemetry_9_to_12_t(); + var msg = new mavlink_global_position_int_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.time_boot_ms = time_boot_ms; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.relative_alt = relative_alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.hdg = hdg; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; + public uint time_boot_ms; - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] + /// Latitude, expressed [degE7] + [Units("[degE7]")] + [Description("Latitude, expressed")] + //[FieldOffset(4)] + public int lat; + + /// Longitude, expressed [degE7] + [Units("[degE7]")] + [Description("Longitude, expressed")] //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; + public int lon; - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] + /// Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.")] + //[FieldOffset(12)] + public int alt; + + /// Altitude above home [mm] + [Units("[mm]")] + [Description("Altitude above home")] //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; + public int relative_alt; - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + /// Ground X Speed (Latitude, positive north) [cm/s] + [Units("[cm/s]")] + [Description("Ground X Speed (Latitude, positive north)")] + //[FieldOffset(20)] + public short vx; - /// count of telemetry packets received (wraps at 65535). - [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + /// Ground Y Speed (Longitude, positive east) [cm/s] + [Units("[cm/s]")] + [Description("Ground Y Speed (Longitude, positive east)")] + //[FieldOffset(22)] + public short vy; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Ground Z Speed (Altitude, positive down) [cm/s] + [Units("[cm/s]")] + [Description("Ground Z Speed (Altitude, positive down)")] + //[FieldOffset(24)] + public short vz; + + /// Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX [cdeg] + [Units("[cdeg]")] + [Description("Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX")] + //[FieldOffset(26)] + public ushort hdg; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - /// Configure an OSD parameter slot. - public struct mavlink_osd_param_config_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] + /// The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. + public struct mavlink_rc_channels_scaled_t { /// packet ordered constructor - public mavlink_osd_param_config_t(uint request_id,float min_value,float max_value,float increment,byte target_system,byte target_component,byte osd_screen,byte osd_index,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type) + public mavlink_rc_channels_scaled_t(uint time_boot_ms,short chan1_scaled,short chan2_scaled,short chan3_scaled,short chan4_scaled,short chan5_scaled,short chan6_scaled,short chan7_scaled,short chan8_scaled,byte port,byte rssi) { - this.request_id = request_id; - this.min_value = min_value; - this.max_value = max_value; - this.increment = increment; - this.target_system = target_system; - this.target_component = target_component; - this.osd_screen = osd_screen; - this.osd_index = osd_index; - this.param_id = param_id; - this.config_type = config_type; + this.time_boot_ms = time_boot_ms; + this.chan1_scaled = chan1_scaled; + this.chan2_scaled = chan2_scaled; + this.chan3_scaled = chan3_scaled; + this.chan4_scaled = chan4_scaled; + this.chan5_scaled = chan5_scaled; + this.chan6_scaled = chan6_scaled; + this.chan7_scaled = chan7_scaled; + this.chan8_scaled = chan8_scaled; + this.port = port; + this.rssi = rssi; } /// packet xml order - public static mavlink_osd_param_config_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,byte osd_screen,byte osd_index,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type,float min_value,float max_value,float increment) + public static mavlink_rc_channels_scaled_t PopulateXMLOrder(uint time_boot_ms,byte port,short chan1_scaled,short chan2_scaled,short chan3_scaled,short chan4_scaled,short chan5_scaled,short chan6_scaled,short chan7_scaled,short chan8_scaled,byte rssi) { - var msg = new mavlink_osd_param_config_t(); + var msg = new mavlink_rc_channels_scaled_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.request_id = request_id; - msg.osd_screen = osd_screen; - msg.osd_index = osd_index; - msg.param_id = param_id; - msg.config_type = config_type; - msg.min_value = min_value; - msg.max_value = max_value; - msg.increment = increment; + msg.time_boot_ms = time_boot_ms; + msg.port = port; + msg.chan1_scaled = chan1_scaled; + msg.chan2_scaled = chan2_scaled; + msg.chan3_scaled = chan3_scaled; + msg.chan4_scaled = chan4_scaled; + msg.chan5_scaled = chan5_scaled; + msg.chan6_scaled = chan6_scaled; + msg.chan7_scaled = chan7_scaled; + msg.chan8_scaled = chan8_scaled; + msg.rssi = rssi; return msg; } - /// Request ID - copied to reply. - [Units("")] - [Description("Request ID - copied to reply.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public uint request_id; + public uint time_boot_ms; - /// OSD parameter minimum value. + /// RC channel 1 value scaled. [Units("")] - [Description("OSD parameter minimum value.")] + [Description("RC channel 1 value scaled.")] //[FieldOffset(4)] - public float min_value; + public short chan1_scaled; - /// OSD parameter maximum value. + /// RC channel 2 value scaled. [Units("")] - [Description("OSD parameter maximum value.")] + [Description("RC channel 2 value scaled.")] + //[FieldOffset(6)] + public short chan2_scaled; + + /// RC channel 3 value scaled. + [Units("")] + [Description("RC channel 3 value scaled.")] //[FieldOffset(8)] - public float max_value; + public short chan3_scaled; - /// OSD parameter increment. + /// RC channel 4 value scaled. [Units("")] - [Description("OSD parameter increment.")] - //[FieldOffset(12)] - public float increment; + [Description("RC channel 4 value scaled.")] + //[FieldOffset(10)] + public short chan4_scaled; - /// System ID. + /// RC channel 5 value scaled. [Units("")] - [Description("System ID.")] - //[FieldOffset(16)] - public byte target_system; + [Description("RC channel 5 value scaled.")] + //[FieldOffset(12)] + public short chan5_scaled; - /// Component ID. + /// RC channel 6 value scaled. [Units("")] - [Description("Component ID.")] - //[FieldOffset(17)] - public byte target_component; + [Description("RC channel 6 value scaled.")] + //[FieldOffset(14)] + public short chan6_scaled; - /// OSD parameter screen index. + /// RC channel 7 value scaled. [Units("")] - [Description("OSD parameter screen index.")] - //[FieldOffset(18)] - public byte osd_screen; + [Description("RC channel 7 value scaled.")] + //[FieldOffset(16)] + public short chan7_scaled; - /// OSD parameter display index. + /// RC channel 8 value scaled. [Units("")] - [Description("OSD parameter display index.")] - //[FieldOffset(19)] - public byte osd_index; + [Description("RC channel 8 value scaled.")] + //[FieldOffset(18)] + public short chan8_scaled; - /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. [Units("")] - [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + [Description("Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.")] //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + public byte port; - /// Config type. OSD_PARAM_CONFIG_TYPE + /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. [Units("")] - [Description("Config type.")] - //[FieldOffset(36)] - public /*OSD_PARAM_CONFIG_TYPE*/byte config_type; + [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(21)] + public byte rssi; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// Configure OSD parameter reply. - public struct mavlink_osd_param_config_reply_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] + /// The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification. + public struct mavlink_rc_channels_raw_t { /// packet ordered constructor - public mavlink_osd_param_config_reply_t(uint request_id,/*OSD_PARAM_CONFIG_ERROR*/byte result) + public mavlink_rc_channels_raw_t(uint time_boot_ms,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,byte port,byte rssi) { - this.request_id = request_id; - this.result = result; + this.time_boot_ms = time_boot_ms; + this.chan1_raw = chan1_raw; + this.chan2_raw = chan2_raw; + this.chan3_raw = chan3_raw; + this.chan4_raw = chan4_raw; + this.chan5_raw = chan5_raw; + this.chan6_raw = chan6_raw; + this.chan7_raw = chan7_raw; + this.chan8_raw = chan8_raw; + this.port = port; + this.rssi = rssi; } /// packet xml order - public static mavlink_osd_param_config_reply_t PopulateXMLOrder(uint request_id,/*OSD_PARAM_CONFIG_ERROR*/byte result) + public static mavlink_rc_channels_raw_t PopulateXMLOrder(uint time_boot_ms,byte port,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,byte rssi) { - var msg = new mavlink_osd_param_config_reply_t(); + var msg = new mavlink_rc_channels_raw_t(); - msg.request_id = request_id; - msg.result = result; + msg.time_boot_ms = time_boot_ms; + msg.port = port; + msg.chan1_raw = chan1_raw; + msg.chan2_raw = chan2_raw; + msg.chan3_raw = chan3_raw; + msg.chan4_raw = chan4_raw; + msg.chan5_raw = chan5_raw; + msg.chan6_raw = chan6_raw; + msg.chan7_raw = chan7_raw; + msg.chan8_raw = chan8_raw; + msg.rssi = rssi; return msg; } - /// Request ID - copied from request. - [Units("")] - [Description("Request ID - copied from request.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public uint request_id; + public uint time_boot_ms; - /// Config error type. OSD_PARAM_CONFIG_ERROR - [Units("")] - [Description("Config error type.")] + /// RC channel 1 value. [us] + [Units("[us]")] + [Description("RC channel 1 value.")] //[FieldOffset(4)] - public /*OSD_PARAM_CONFIG_ERROR*/byte result; + public ushort chan1_raw; + + /// RC channel 2 value. [us] + [Units("[us]")] + [Description("RC channel 2 value.")] + //[FieldOffset(6)] + public ushort chan2_raw; + + /// RC channel 3 value. [us] + [Units("[us]")] + [Description("RC channel 3 value.")] + //[FieldOffset(8)] + public ushort chan3_raw; + + /// RC channel 4 value. [us] + [Units("[us]")] + [Description("RC channel 4 value.")] + //[FieldOffset(10)] + public ushort chan4_raw; + + /// RC channel 5 value. [us] + [Units("[us]")] + [Description("RC channel 5 value.")] + //[FieldOffset(12)] + public ushort chan5_raw; + + /// RC channel 6 value. [us] + [Units("[us]")] + [Description("RC channel 6 value.")] + //[FieldOffset(14)] + public ushort chan6_raw; + + /// RC channel 7 value. [us] + [Units("[us]")] + [Description("RC channel 7 value.")] + //[FieldOffset(16)] + public ushort chan7_raw; + + /// RC channel 8 value. [us] + [Units("[us]")] + [Description("RC channel 8 value.")] + //[FieldOffset(18)] + public ushort chan8_raw; + + /// Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + [Units("")] + [Description("Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.")] + //[FieldOffset(20)] + public byte port; + + /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + [Units("")] + [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(21)] + public byte rssi; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// Read a configured an OSD parameter slot. - public struct mavlink_osd_param_show_config_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] + /// Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + public struct mavlink_servo_output_raw_t { /// packet ordered constructor - public mavlink_osd_param_show_config_t(uint request_id,byte target_system,byte target_component,byte osd_screen,byte osd_index) + public mavlink_servo_output_raw_t(uint time_usec,ushort servo1_raw,ushort servo2_raw,ushort servo3_raw,ushort servo4_raw,ushort servo5_raw,ushort servo6_raw,ushort servo7_raw,ushort servo8_raw,byte port,ushort servo9_raw,ushort servo10_raw,ushort servo11_raw,ushort servo12_raw,ushort servo13_raw,ushort servo14_raw,ushort servo15_raw,ushort servo16_raw) { - this.request_id = request_id; - this.target_system = target_system; - this.target_component = target_component; - this.osd_screen = osd_screen; - this.osd_index = osd_index; + this.time_usec = time_usec; + this.servo1_raw = servo1_raw; + this.servo2_raw = servo2_raw; + this.servo3_raw = servo3_raw; + this.servo4_raw = servo4_raw; + this.servo5_raw = servo5_raw; + this.servo6_raw = servo6_raw; + this.servo7_raw = servo7_raw; + this.servo8_raw = servo8_raw; + this.port = port; + this.servo9_raw = servo9_raw; + this.servo10_raw = servo10_raw; + this.servo11_raw = servo11_raw; + this.servo12_raw = servo12_raw; + this.servo13_raw = servo13_raw; + this.servo14_raw = servo14_raw; + this.servo15_raw = servo15_raw; + this.servo16_raw = servo16_raw; } /// packet xml order - public static mavlink_osd_param_show_config_t PopulateXMLOrder(byte target_system,byte target_component,uint request_id,byte osd_screen,byte osd_index) + public static mavlink_servo_output_raw_t PopulateXMLOrder(uint time_usec,byte port,ushort servo1_raw,ushort servo2_raw,ushort servo3_raw,ushort servo4_raw,ushort servo5_raw,ushort servo6_raw,ushort servo7_raw,ushort servo8_raw,ushort servo9_raw,ushort servo10_raw,ushort servo11_raw,ushort servo12_raw,ushort servo13_raw,ushort servo14_raw,ushort servo15_raw,ushort servo16_raw) { - var msg = new mavlink_osd_param_show_config_t(); + var msg = new mavlink_servo_output_raw_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.request_id = request_id; - msg.osd_screen = osd_screen; - msg.osd_index = osd_index; + msg.time_usec = time_usec; + msg.port = port; + msg.servo1_raw = servo1_raw; + msg.servo2_raw = servo2_raw; + msg.servo3_raw = servo3_raw; + msg.servo4_raw = servo4_raw; + msg.servo5_raw = servo5_raw; + msg.servo6_raw = servo6_raw; + msg.servo7_raw = servo7_raw; + msg.servo8_raw = servo8_raw; + msg.servo9_raw = servo9_raw; + msg.servo10_raw = servo10_raw; + msg.servo11_raw = servo11_raw; + msg.servo12_raw = servo12_raw; + msg.servo13_raw = servo13_raw; + msg.servo14_raw = servo14_raw; + msg.servo15_raw = servo15_raw; + msg.servo16_raw = servo16_raw; return msg; } - /// Request ID - copied to reply. - [Units("")] - [Description("Request ID - copied to reply.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint request_id; + public uint time_usec; - /// System ID. - [Units("")] - [Description("System ID.")] + /// Servo output 1 value [us] + [Units("[us]")] + [Description("Servo output 1 value")] //[FieldOffset(4)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + public ushort servo1_raw; - /// OSD parameter screen index. - [Units("")] - [Description("OSD parameter screen index.")] + /// Servo output 2 value [us] + [Units("[us]")] + [Description("Servo output 2 value")] //[FieldOffset(6)] - public byte osd_screen; + public ushort servo2_raw; - /// OSD parameter display index. + /// Servo output 3 value [us] + [Units("[us]")] + [Description("Servo output 3 value")] + //[FieldOffset(8)] + public ushort servo3_raw; + + /// Servo output 4 value [us] + [Units("[us]")] + [Description("Servo output 4 value")] + //[FieldOffset(10)] + public ushort servo4_raw; + + /// Servo output 5 value [us] + [Units("[us]")] + [Description("Servo output 5 value")] + //[FieldOffset(12)] + public ushort servo5_raw; + + /// Servo output 6 value [us] + [Units("[us]")] + [Description("Servo output 6 value")] + //[FieldOffset(14)] + public ushort servo6_raw; + + /// Servo output 7 value [us] + [Units("[us]")] + [Description("Servo output 7 value")] + //[FieldOffset(16)] + public ushort servo7_raw; + + /// Servo output 8 value [us] + [Units("[us]")] + [Description("Servo output 8 value")] + //[FieldOffset(18)] + public ushort servo8_raw; + + /// Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. [Units("")] - [Description("OSD parameter display index.")] - //[FieldOffset(7)] - public byte osd_index; + [Description("Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.")] + //[FieldOffset(20)] + public byte port; + + /// Servo output 9 value [us] + [Units("[us]")] + [Description("Servo output 9 value")] + //[FieldOffset(21)] + public ushort servo9_raw; + + /// Servo output 10 value [us] + [Units("[us]")] + [Description("Servo output 10 value")] + //[FieldOffset(23)] + public ushort servo10_raw; + + /// Servo output 11 value [us] + [Units("[us]")] + [Description("Servo output 11 value")] + //[FieldOffset(25)] + public ushort servo11_raw; + + /// Servo output 12 value [us] + [Units("[us]")] + [Description("Servo output 12 value")] + //[FieldOffset(27)] + public ushort servo12_raw; + + /// Servo output 13 value [us] + [Units("[us]")] + [Description("Servo output 13 value")] + //[FieldOffset(29)] + public ushort servo13_raw; + + /// Servo output 14 value [us] + [Units("[us]")] + [Description("Servo output 14 value")] + //[FieldOffset(31)] + public ushort servo14_raw; + + /// Servo output 15 value [us] + [Units("[us]")] + [Description("Servo output 15 value")] + //[FieldOffset(33)] + public ushort servo15_raw; + + /// Servo output 16 value [us] + [Units("[us]")] + [Description("Servo output 16 value")] + //[FieldOffset(35)] + public ushort servo16_raw; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] - /// Read configured OSD parameter reply. - public struct mavlink_osd_param_show_config_reply_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] + /// Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint. + public struct mavlink_mission_request_partial_list_t { /// packet ordered constructor - public mavlink_osd_param_show_config_reply_t(uint request_id,float min_value,float max_value,float increment,/*OSD_PARAM_CONFIG_ERROR*/byte result,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type) + public mavlink_mission_request_partial_list_t(short start_index,short end_index,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.request_id = request_id; - this.min_value = min_value; - this.max_value = max_value; - this.increment = increment; - this.result = result; - this.param_id = param_id; - this.config_type = config_type; + this.start_index = start_index; + this.end_index = end_index; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_osd_param_show_config_reply_t PopulateXMLOrder(uint request_id,/*OSD_PARAM_CONFIG_ERROR*/byte result,byte[] param_id,/*OSD_PARAM_CONFIG_TYPE*/byte config_type,float min_value,float max_value,float increment) + public static mavlink_mission_request_partial_list_t PopulateXMLOrder(byte target_system,byte target_component,short start_index,short end_index,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_osd_param_show_config_reply_t(); + var msg = new mavlink_mission_request_partial_list_t(); - msg.request_id = request_id; - msg.result = result; - msg.param_id = param_id; - msg.config_type = config_type; - msg.min_value = min_value; - msg.max_value = max_value; - msg.increment = increment; + msg.target_system = target_system; + msg.target_component = target_component; + msg.start_index = start_index; + msg.end_index = end_index; + msg.mission_type = mission_type; return msg; } - /// Request ID - copied from request. + /// Start index [Units("")] - [Description("Request ID - copied from request.")] + [Description("Start index")] //[FieldOffset(0)] - public uint request_id; - - /// OSD parameter minimum value. - [Units("")] - [Description("OSD parameter minimum value.")] - //[FieldOffset(4)] - public float min_value; - - /// OSD parameter maximum value. - [Units("")] - [Description("OSD parameter maximum value.")] - //[FieldOffset(8)] - public float max_value; + public short start_index; - /// OSD parameter increment. + /// End index, -1 by default (-1: send list to end). Else a valid index of the list [Units("")] - [Description("OSD parameter increment.")] - //[FieldOffset(12)] - public float increment; + [Description("End index, -1 by default (-1: send list to end). Else a valid index of the list")] + //[FieldOffset(2)] + public short end_index; - /// Config error type. OSD_PARAM_CONFIG_ERROR - [Units("")] - [Description("Config error type.")] - //[FieldOffset(16)] - public /*OSD_PARAM_CONFIG_ERROR*/byte result; + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(4)] + public byte target_system; - /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Component ID [Units("")] - [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(17)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [Description("Component ID")] + //[FieldOffset(5)] + public byte target_component; - /// Config type. OSD_PARAM_CONFIG_TYPE + /// Mission type. MAV_MISSION_TYPE [Units("")] - [Description("Config type.")] - //[FieldOffset(33)] - public /*OSD_PARAM_CONFIG_TYPE*/byte config_type; + [Description("Mission type.")] + //[FieldOffset(6)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// Obstacle located as a 3D vector. - public struct mavlink_obstacle_distance_3d_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] + /// This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! + public struct mavlink_mission_write_partial_list_t { /// packet ordered constructor - public mavlink_obstacle_distance_3d_t(uint time_boot_ms,float x,float y,float z,float min_distance,float max_distance,ushort obstacle_id,/*MAV_DISTANCE_SENSOR*/byte sensor_type,/*MAV_FRAME*/byte frame) + public mavlink_mission_write_partial_list_t(short start_index,short end_index,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.time_boot_ms = time_boot_ms; - this.x = x; - this.y = y; - this.z = z; - this.min_distance = min_distance; - this.max_distance = max_distance; - this.obstacle_id = obstacle_id; - this.sensor_type = sensor_type; - this.frame = frame; + this.start_index = start_index; + this.end_index = end_index; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_obstacle_distance_3d_t PopulateXMLOrder(uint time_boot_ms,/*MAV_DISTANCE_SENSOR*/byte sensor_type,/*MAV_FRAME*/byte frame,ushort obstacle_id,float x,float y,float z,float min_distance,float max_distance) + public static mavlink_mission_write_partial_list_t PopulateXMLOrder(byte target_system,byte target_component,short start_index,short end_index,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_obstacle_distance_3d_t(); + var msg = new mavlink_mission_write_partial_list_t(); - msg.time_boot_ms = time_boot_ms; - msg.sensor_type = sensor_type; - msg.frame = frame; - msg.obstacle_id = obstacle_id; - msg.x = x; - msg.y = y; - msg.z = z; - msg.min_distance = min_distance; - msg.max_distance = max_distance; + msg.target_system = target_system; + msg.target_component = target_component; + msg.start_index = start_index; + msg.end_index = end_index; + msg.mission_type = mission_type; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Start index. Must be smaller / equal to the largest index of the current onboard list. + [Units("")] + [Description("Start index. Must be smaller / equal to the largest index of the current onboard list.")] //[FieldOffset(0)] - public uint time_boot_ms; - - /// X position of the obstacle. [m] - [Units("[m]")] - [Description(" X position of the obstacle.")] - //[FieldOffset(4)] - public float x; - - /// Y position of the obstacle. [m] - [Units("[m]")] - [Description(" Y position of the obstacle.")] - //[FieldOffset(8)] - public float y; - - /// Z position of the obstacle. [m] - [Units("[m]")] - [Description(" Z position of the obstacle.")] - //[FieldOffset(12)] - public float z; - - /// Minimum distance the sensor can measure. [m] - [Units("[m]")] - [Description("Minimum distance the sensor can measure.")] - //[FieldOffset(16)] - public float min_distance; + public short start_index; - /// Maximum distance the sensor can measure. [m] - [Units("[m]")] - [Description("Maximum distance the sensor can measure.")] - //[FieldOffset(20)] - public float max_distance; + /// End index, equal or greater than start index. + [Units("")] + [Description("End index, equal or greater than start index.")] + //[FieldOffset(2)] + public short end_index; - /// Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined. + /// System ID [Units("")] - [Description(" Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.")] - //[FieldOffset(24)] - public ushort obstacle_id; + [Description("System ID")] + //[FieldOffset(4)] + public byte target_system; - /// Class id of the distance sensor type. MAV_DISTANCE_SENSOR + /// Component ID [Units("")] - [Description("Class id of the distance sensor type.")] - //[FieldOffset(26)] - public /*MAV_DISTANCE_SENSOR*/byte sensor_type; + [Description("Component ID")] + //[FieldOffset(5)] + public byte target_component; - /// Coordinate frame of reference. MAV_FRAME + /// Mission type. MAV_MISSION_TYPE [Units("")] - [Description("Coordinate frame of reference.")] - //[FieldOffset(27)] - public /*MAV_FRAME*/byte frame; + [Description("Mission type.")] + //[FieldOffset(6)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - - /// extensions_start 0 + [Obsolete] + /// extensions_start 14 [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] - /// Water depth - public struct mavlink_water_depth_t + /// Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html. + public struct mavlink_mission_item_t { /// packet ordered constructor - public mavlink_water_depth_t(uint time_boot_ms,int lat,int lng,float alt,float roll,float pitch,float yaw,float distance,float temperature,byte id,byte healthy) + public mavlink_mission_item_t(float param1,float param2,float param3,float param4,float x,float y,float z,ushort seq,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue,/*MAV_MISSION_TYPE*/byte mission_type) { - this.time_boot_ms = time_boot_ms; - this.lat = lat; - this.lng = lng; - this.alt = alt; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.distance = distance; - this.temperature = temperature; - this.id = id; - this.healthy = healthy; + this.param1 = param1; + this.param2 = param2; + this.param3 = param3; + this.param4 = param4; + this.x = x; + this.y = y; + this.z = z; + this.seq = seq; + this.command = command; + this.target_system = target_system; + this.target_component = target_component; + this.frame = frame; + this.current = current; + this.autocontinue = autocontinue; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_water_depth_t PopulateXMLOrder(uint time_boot_ms,byte id,byte healthy,int lat,int lng,float alt,float roll,float pitch,float yaw,float distance,float temperature) + public static mavlink_mission_item_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_water_depth_t(); + var msg = new mavlink_mission_item_t(); - msg.time_boot_ms = time_boot_ms; - msg.id = id; - msg.healthy = healthy; - msg.lat = lat; - msg.lng = lng; - msg.alt = alt; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.distance = distance; - msg.temperature = temperature; + msg.target_system = target_system; + msg.target_component = target_component; + msg.seq = seq; + msg.frame = frame; + msg.command = command; + msg.current = current; + msg.autocontinue = autocontinue; + msg.param1 = param1; + msg.param2 = param2; + msg.param3 = param3; + msg.param4 = param4; + msg.x = x; + msg.y = y; + msg.z = z; + msg.mission_type = mission_type; return msg; } - /// Timestamp (time since system boot) [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot)")] + /// PARAM1, see MAV_CMD enum + [Units("")] + [Description("PARAM1, see MAV_CMD enum")] //[FieldOffset(0)] - public uint time_boot_ms; + public float param1; - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] + /// PARAM2, see MAV_CMD enum + [Units("")] + [Description("PARAM2, see MAV_CMD enum")] //[FieldOffset(4)] - public int lat; + public float param2; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] + /// PARAM3, see MAV_CMD enum + [Units("")] + [Description("PARAM3, see MAV_CMD enum")] //[FieldOffset(8)] - public int lng; + public float param3; - /// Altitude (MSL) of vehicle [m] - [Units("[m]")] - [Description("Altitude (MSL) of vehicle")] + /// PARAM4, see MAV_CMD enum + [Units("")] + [Description("PARAM4, see MAV_CMD enum")] //[FieldOffset(12)] - public float alt; + public float param4; - /// Roll angle [rad] - [Units("[rad]")] - [Description("Roll angle")] + /// PARAM5 / local: X coordinate, global: latitude + [Units("")] + [Description("PARAM5 / local: X coordinate, global: latitude")] //[FieldOffset(16)] - public float roll; + public float x; - /// Pitch angle [rad] - [Units("[rad]")] - [Description("Pitch angle")] + /// PARAM6 / local: Y coordinate, global: longitude + [Units("")] + [Description("PARAM6 / local: Y coordinate, global: longitude")] //[FieldOffset(20)] - public float pitch; + public float y; - /// Yaw angle [rad] - [Units("[rad]")] - [Description("Yaw angle")] + /// PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). + [Units("")] + [Description("PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).")] //[FieldOffset(24)] - public float yaw; + public float z; - /// Distance (uncorrected) [m] - [Units("[m]")] - [Description("Distance (uncorrected)")] + /// Sequence + [Units("")] + [Description("Sequence")] //[FieldOffset(28)] - public float distance; - - /// Water temperature [degC] - [Units("[degC]")] - [Description("Water temperature")] - //[FieldOffset(32)] - public float temperature; + public ushort seq; - /// Onboard ID of the sensor + /// The scheduled action for the waypoint. MAV_CMD [Units("")] - [Description("Onboard ID of the sensor")] - //[FieldOffset(36)] - public byte id; + [Description("The scheduled action for the waypoint.")] + //[FieldOffset(30)] + public /*MAV_CMD*/ushort command; - /// Sensor data healthy (0=unhealthy, 1=healthy) + /// System ID [Units("")] - [Description("Sensor data healthy (0=unhealthy, 1=healthy)")] - //[FieldOffset(37)] - public byte healthy; - }; - - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// The MCU status, giving MCU temperature and voltage. The min and max voltages are to allow for detecting power supply instability. - public struct mavlink_mcu_status_t - { - /// packet ordered constructor - public mavlink_mcu_status_t(short MCU_temperature,ushort MCU_voltage,ushort MCU_voltage_min,ushort MCU_voltage_max,byte id) - { - this.MCU_temperature = MCU_temperature; - this.MCU_voltage = MCU_voltage; - this.MCU_voltage_min = MCU_voltage_min; - this.MCU_voltage_max = MCU_voltage_max; - this.id = id; - - } - - /// packet xml order - public static mavlink_mcu_status_t PopulateXMLOrder(byte id,short MCU_temperature,ushort MCU_voltage,ushort MCU_voltage_min,ushort MCU_voltage_max) - { - var msg = new mavlink_mcu_status_t(); - - msg.id = id; - msg.MCU_temperature = MCU_temperature; - msg.MCU_voltage = MCU_voltage; - msg.MCU_voltage_min = MCU_voltage_min; - msg.MCU_voltage_max = MCU_voltage_max; - - return msg; - } - + [Description("System ID")] + //[FieldOffset(32)] + public byte target_system; - /// MCU Internal temperature [cdegC] - [Units("[cdegC]")] - [Description("MCU Internal temperature")] - //[FieldOffset(0)] - public short MCU_temperature; + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(33)] + public byte target_component; - /// MCU voltage [mV] - [Units("[mV]")] - [Description("MCU voltage")] - //[FieldOffset(2)] - public ushort MCU_voltage; + /// The coordinate system of the waypoint. MAV_FRAME + [Units("")] + [Description("The coordinate system of the waypoint.")] + //[FieldOffset(34)] + public /*MAV_FRAME*/byte frame; - /// MCU voltage minimum [mV] - [Units("[mV]")] - [Description("MCU voltage minimum")] - //[FieldOffset(4)] - public ushort MCU_voltage_min; + /// false:0, true:1 + [Units("")] + [Description("false:0, true:1")] + //[FieldOffset(35)] + public byte current; - /// MCU voltage maximum [mV] - [Units("[mV]")] - [Description("MCU voltage maximum")] - //[FieldOffset(6)] - public ushort MCU_voltage_max; + /// Autocontinue to next waypoint + [Units("")] + [Description("Autocontinue to next waypoint")] + //[FieldOffset(36)] + public byte autocontinue; - /// MCU instance + /// Mission type. MAV_MISSION_TYPE [Units("")] - [Description("MCU instance")] - //[FieldOffset(8)] - public byte id; + [Description("Mission type.")] + //[FieldOffset(37)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 13 to 16, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_13_to_16_t + [Obsolete] + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html + public struct mavlink_mission_request_t { /// packet ordered constructor - public mavlink_esc_telemetry_13_to_16_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_mission_request_t(ushort seq,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.seq = seq; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_esc_telemetry_13_to_16_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_mission_request_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_esc_telemetry_13_to_16_t(); + var msg = new mavlink_mission_request_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.target_system = target_system; + msg.target_component = target_component; + msg.seq = seq; + msg.mission_type = mission_type; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Sequence + [Units("")] + [Description("Sequence")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; - - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; - - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; + public ushort seq; - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(2)] + public byte target_system; - /// count of telemetry packets received (wraps at 65535). + /// Component ID [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + [Description("Component ID")] + //[FieldOffset(3)] + public byte target_component; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Mission type. MAV_MISSION_TYPE + [Units("")] + [Description("Mission type.")] + //[FieldOffset(4)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 17 to 20, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_17_to_20_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// 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). + public struct mavlink_mission_set_current_t { /// packet ordered constructor - public mavlink_esc_telemetry_17_to_20_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_mission_set_current_t(ushort seq,byte target_system,byte target_component) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.seq = seq; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_esc_telemetry_17_to_20_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_mission_set_current_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq) { - var msg = new mavlink_esc_telemetry_17_to_20_t(); + var msg = new mavlink_mission_set_current_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.target_system = target_system; + msg.target_component = target_component; + msg.seq = seq; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Sequence + [Units("")] + [Description("Sequence")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; - - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; - - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; - - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + public ushort seq; - /// count of telemetry packets received (wraps at 65535). + /// System ID [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + [Description("System ID")] + //[FieldOffset(2)] + public byte target_system; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(3)] + public byte target_component; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 21 to 24, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_21_to_24_t + /// extensions_start 1 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. + public struct mavlink_mission_current_t { /// packet ordered constructor - public mavlink_esc_telemetry_21_to_24_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_mission_current_t(ushort seq,ushort total,/*MISSION_STATE*/byte mission_state,byte mission_mode) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.seq = seq; + this.total = total; + this.mission_state = mission_state; + this.mission_mode = mission_mode; } /// packet xml order - public static mavlink_esc_telemetry_21_to_24_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_mission_current_t PopulateXMLOrder(ushort seq,ushort total,/*MISSION_STATE*/byte mission_state,byte mission_mode) { - var msg = new mavlink_esc_telemetry_21_to_24_t(); + var msg = new mavlink_mission_current_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.seq = seq; + msg.total = total; + msg.mission_state = mission_state; + msg.mission_mode = mission_mode; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Sequence + [Units("")] + [Description("Sequence")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; - - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; - - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; + public ushort seq; - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + /// Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. + [Units("")] + [Description("Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.")] + //[FieldOffset(2)] + public ushort total; - /// count of telemetry packets received (wraps at 65535). + /// Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. MISSION_STATE [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + [Description("Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.")] + //[FieldOffset(4)] + public /*MISSION_STATE*/byte mission_state; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). + [Units("")] + [Description("Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).")] + //[FieldOffset(5)] + public byte mission_mode; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 25 to 28, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_25_to_28_t + /// extensions_start 2 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Request the overall list of mission items from the system/component. + public struct mavlink_mission_request_list_t { /// packet ordered constructor - public mavlink_esc_telemetry_25_to_28_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_mission_request_list_t(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; - this.count = count; - this.temperature = temperature; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_esc_telemetry_25_to_28_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_mission_request_list_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_esc_telemetry_25_to_28_t(); + var msg = new mavlink_mission_request_list_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; - msg.count = count; + msg.target_system = target_system; + msg.target_component = target_component; + msg.mission_type = mission_type; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// System ID + [Units("")] + [Description("System ID")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; - - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; - - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; - - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + public byte target_system; - /// count of telemetry packets received (wraps at 65535). + /// Component ID [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Mission type. MAV_MISSION_TYPE + [Units("")] + [Description("Mission type.")] + //[FieldOffset(2)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// ESC Telemetry Data for ESCs 29 to 32, matching data sent by BLHeli ESCs. - public struct mavlink_esc_telemetry_29_to_32_t + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints. + public struct mavlink_mission_count_t { /// packet ordered constructor - public mavlink_esc_telemetry_29_to_32_t(ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count,byte[] temperature) + public mavlink_mission_count_t(ushort count,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.voltage = voltage; - this.current = current; - this.totalcurrent = totalcurrent; - this.rpm = rpm; this.count = count; - this.temperature = temperature; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_esc_telemetry_29_to_32_t PopulateXMLOrder(byte[] temperature,ushort[] voltage,ushort[] current,ushort[] totalcurrent,ushort[] rpm,ushort[] count) + public static mavlink_mission_count_t PopulateXMLOrder(byte target_system,byte target_component,ushort count,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_esc_telemetry_29_to_32_t(); + var msg = new mavlink_mission_count_t(); - msg.temperature = temperature; - msg.voltage = voltage; - msg.current = current; - msg.totalcurrent = totalcurrent; - msg.rpm = rpm; + msg.target_system = target_system; + msg.target_component = target_component; msg.count = count; + msg.mission_type = mission_type; return msg; } - /// Voltage. [cV] - [Units("[cV]")] - [Description("Voltage.")] + /// Number of mission items in the sequence + [Units("")] + [Description("Number of mission items in the sequence")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltage; - - /// Current. [cA] - [Units("[cA]")] - [Description("Current.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] current; - - /// Total current. [mAh] - [Units("[mAh]")] - [Description("Total current.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] totalcurrent; + public ushort count; - /// RPM (eRPM). [rpm] - [Units("[rpm]")] - [Description("RPM (eRPM).")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] rpm; + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(2)] + public byte target_system; - /// count of telemetry packets received (wraps at 65535). + /// Component ID [Units("")] - [Description("count of telemetry packets received (wraps at 65535).")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] count; + [Description("Component ID")] + //[FieldOffset(3)] + public byte target_component; - /// Temperature. [degC] - [Units("[degC]")] - [Description("Temperature.")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] temperature; + /// Mission type. MAV_MISSION_TYPE + [Units("")] + [Description("Mission type.")] + //[FieldOffset(4)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=246)] - /// Information about video stream - public struct mavlink_video_stream_information99_t + + /// extensions_start 2 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// Delete all mission items at once. + public struct mavlink_mission_clear_all_t { /// packet ordered constructor - public mavlink_video_stream_information99_t(float framerate,uint bitrate,ushort resolution_h,ushort resolution_v,ushort rotation,byte camera_id,byte status,byte[] uri) + public mavlink_mission_clear_all_t(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.framerate = framerate; - this.bitrate = bitrate; - this.resolution_h = resolution_h; - this.resolution_v = resolution_v; - this.rotation = rotation; - this.camera_id = camera_id; - this.status = status; - this.uri = uri; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_video_stream_information99_t PopulateXMLOrder(byte camera_id,byte status,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,byte[] uri) + public static mavlink_mission_clear_all_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_video_stream_information99_t(); + var msg = new mavlink_mission_clear_all_t(); - msg.camera_id = camera_id; - msg.status = status; - msg.framerate = framerate; - msg.resolution_h = resolution_h; - msg.resolution_v = resolution_v; - msg.bitrate = bitrate; - msg.rotation = rotation; - msg.uri = uri; + msg.target_system = target_system; + msg.target_component = target_component; + msg.mission_type = mission_type; return msg; } - /// Frame rate. [Hz] - [Units("[Hz]")] - [Description("Frame rate.")] - //[FieldOffset(0)] - public float framerate; - - /// Bit rate. [bits/s] - [Units("[bits/s]")] - [Description("Bit rate.")] - //[FieldOffset(4)] - public uint bitrate; - - /// Horizontal resolution. [pix] - [Units("[pix]")] - [Description("Horizontal resolution.")] - //[FieldOffset(8)] - public ushort resolution_h; - - /// Vertical resolution. [pix] - [Units("[pix]")] - [Description("Vertical resolution.")] - //[FieldOffset(10)] - public ushort resolution_v; - - /// Video image rotation clockwise. [deg] - [Units("[deg]")] - [Description("Video image rotation clockwise.")] - //[FieldOffset(12)] - public ushort rotation; - - /// Video Stream ID (1 for first, 2 for second, etc.) + /// System ID [Units("")] - [Description("Video Stream ID (1 for first, 2 for second, etc.)")] - //[FieldOffset(14)] - public byte camera_id; + [Description("System ID")] + //[FieldOffset(0)] + public byte target_system; - /// Number of streams available. + /// Component ID [Units("")] - [Description("Number of streams available.")] - //[FieldOffset(15)] - public byte status; + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; - /// Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). + /// Mission type. MAV_MISSION_TYPE [Units("")] - [Description("Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=230)] - public byte[] uri; + [Description("Mission type.")] + //[FieldOffset(2)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)] - /// The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. - public struct mavlink_sys_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. + public struct mavlink_mission_item_reached_t { /// packet ordered constructor - public mavlink_sys_status_t(/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_present,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_enabled,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_health,ushort load,ushort voltage_battery,short current_battery,ushort drop_rate_comm,ushort errors_comm,ushort errors_count1,ushort errors_count2,ushort errors_count3,ushort errors_count4,sbyte battery_remaining) + public mavlink_mission_item_reached_t(ushort seq) { - this.onboard_control_sensors_present = onboard_control_sensors_present; - this.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - this.onboard_control_sensors_health = onboard_control_sensors_health; - this.load = load; - this.voltage_battery = voltage_battery; - this.current_battery = current_battery; - this.drop_rate_comm = drop_rate_comm; - this.errors_comm = errors_comm; - this.errors_count1 = errors_count1; - this.errors_count2 = errors_count2; - this.errors_count3 = errors_count3; - this.errors_count4 = errors_count4; - this.battery_remaining = battery_remaining; + this.seq = seq; } /// packet xml order - public static mavlink_sys_status_t PopulateXMLOrder(/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_present,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_enabled,/*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_health,ushort load,ushort voltage_battery,short current_battery,sbyte battery_remaining,ushort drop_rate_comm,ushort errors_comm,ushort errors_count1,ushort errors_count2,ushort errors_count3,ushort errors_count4) + public static mavlink_mission_item_reached_t PopulateXMLOrder(ushort seq) { - var msg = new mavlink_sys_status_t(); + var msg = new mavlink_mission_item_reached_t(); - msg.onboard_control_sensors_present = onboard_control_sensors_present; - msg.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - msg.onboard_control_sensors_health = onboard_control_sensors_health; - msg.load = load; - msg.voltage_battery = voltage_battery; - msg.current_battery = current_battery; - msg.battery_remaining = battery_remaining; - msg.drop_rate_comm = drop_rate_comm; - msg.errors_comm = errors_comm; - msg.errors_count1 = errors_count1; - msg.errors_count2 = errors_count2; - msg.errors_count3 = errors_count3; - msg.errors_count4 = errors_count4; + msg.seq = seq; return msg; } - /// Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. MAV_SYS_STATUS_SENSOR bitmask + /// Sequence [Units("")] - [Description("Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.")] + [Description("Sequence")] //[FieldOffset(0)] - public /*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_present; - - /// Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. MAV_SYS_STATUS_SENSOR bitmask - [Units("")] - [Description("Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.")] - //[FieldOffset(4)] - public /*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_enabled; - - /// Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. MAV_SYS_STATUS_SENSOR bitmask - [Units("")] - [Description("Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.")] - //[FieldOffset(8)] - public /*MAV_SYS_STATUS_SENSOR*/uint onboard_control_sensors_health; - - /// Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 [d%] - [Units("[d%]")] - [Description("Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000")] - //[FieldOffset(12)] - public ushort load; - - /// Battery voltage, UINT16_MAX: Voltage not sent by autopilot [mV] - [Units("[mV]")] - [Description("Battery voltage, UINT16_MAX: Voltage not sent by autopilot")] - //[FieldOffset(14)] - public ushort voltage_battery; - - /// Battery current, -1: Current not sent by autopilot [cA] - [Units("[cA]")] - [Description("Battery current, -1: Current not sent by autopilot")] - //[FieldOffset(16)] - public short current_battery; - - /// Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) [c%] - [Units("[c%]")] - [Description("Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)")] - //[FieldOffset(18)] - public ushort drop_rate_comm; + public ushort seq; + }; - /// Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - [Units("")] - [Description("Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)")] - //[FieldOffset(20)] - public ushort errors_comm; + + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + public struct mavlink_mission_ack_t + { + /// packet ordered constructor + public mavlink_mission_ack_t(byte target_system,byte target_component,/*MAV_MISSION_RESULT*/byte type,/*MAV_MISSION_TYPE*/byte mission_type) + { + this.target_system = target_system; + this.target_component = target_component; + this.type = type; + this.mission_type = mission_type; + + } + + /// packet xml order + public static mavlink_mission_ack_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MISSION_RESULT*/byte type,/*MAV_MISSION_TYPE*/byte mission_type) + { + var msg = new mavlink_mission_ack_t(); - /// Autopilot-specific errors - [Units("")] - [Description("Autopilot-specific errors")] - //[FieldOffset(22)] - public ushort errors_count1; + msg.target_system = target_system; + msg.target_component = target_component; + msg.type = type; + msg.mission_type = mission_type; + + return msg; + } + - /// Autopilot-specific errors + /// System ID [Units("")] - [Description("Autopilot-specific errors")] - //[FieldOffset(24)] - public ushort errors_count2; + [Description("System ID")] + //[FieldOffset(0)] + public byte target_system; - /// Autopilot-specific errors + /// Component ID [Units("")] - [Description("Autopilot-specific errors")] - //[FieldOffset(26)] - public ushort errors_count3; + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; - /// Autopilot-specific errors + /// Mission result. MAV_MISSION_RESULT [Units("")] - [Description("Autopilot-specific errors")] - //[FieldOffset(28)] - public ushort errors_count4; - - /// Battery energy remaining, -1: Battery remaining energy not sent by autopilot [%] - [Units("[%]")] - [Description("Battery energy remaining, -1: Battery remaining energy not sent by autopilot")] - //[FieldOffset(30)] - public sbyte battery_remaining; + [Description("Mission result.")] + //[FieldOffset(2)] + public /*MAV_MISSION_RESULT*/byte type; + + /// Mission type. MAV_MISSION_TYPE + [Units("")] + [Description("Mission type.")] + //[FieldOffset(3)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - /// The system time is the time of the master clock, typically the computer clock of the main onboard computer. - public struct mavlink_system_time_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)] + /// Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor. + public struct mavlink_set_gps_global_origin_t { /// packet ordered constructor - public mavlink_system_time_t(ulong time_unix_usec,uint time_boot_ms) + public mavlink_set_gps_global_origin_t(int latitude,int longitude,int altitude,byte target_system,ulong time_usec) { - this.time_unix_usec = time_unix_usec; - this.time_boot_ms = time_boot_ms; + this.latitude = latitude; + this.longitude = longitude; + this.altitude = altitude; + this.target_system = target_system; + this.time_usec = time_usec; } /// packet xml order - public static mavlink_system_time_t PopulateXMLOrder(ulong time_unix_usec,uint time_boot_ms) + public static mavlink_set_gps_global_origin_t PopulateXMLOrder(byte target_system,int latitude,int longitude,int altitude,ulong time_usec) { - var msg = new mavlink_system_time_t(); + var msg = new mavlink_set_gps_global_origin_t(); - msg.time_unix_usec = time_unix_usec; - msg.time_boot_ms = time_boot_ms; + msg.target_system = target_system; + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude = altitude; + msg.time_usec = time_usec; return msg; } - /// Timestamp (UNIX epoch time). [us] - [Units("[us]")] - [Description("Timestamp (UNIX epoch time).")] + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] //[FieldOffset(0)] - public ulong time_unix_usec; + public int latitude; - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] + //[FieldOffset(4)] + public int longitude; + + /// Altitude (MSL). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Positive for up.")] //[FieldOffset(8)] - public uint time_boot_ms; + public int altitude; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(12)] + public byte target_system; + + /// 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. [us] + [Units("[us]")] + [Description("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.")] + //[FieldOffset(13)] + public ulong time_usec; }; - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - /// A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html - public struct mavlink_ping_t + + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Publishes the GPS co-ordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message. + public struct mavlink_gps_global_origin_t { /// packet ordered constructor - public mavlink_ping_t(ulong time_usec,uint seq,byte target_system,byte target_component) + public mavlink_gps_global_origin_t(int latitude,int longitude,int altitude,ulong time_usec) { + this.latitude = latitude; + this.longitude = longitude; + this.altitude = altitude; this.time_usec = time_usec; - this.seq = seq; - this.target_system = target_system; - this.target_component = target_component; } /// packet xml order - public static mavlink_ping_t PopulateXMLOrder(ulong time_usec,uint seq,byte target_system,byte target_component) + public static mavlink_gps_global_origin_t PopulateXMLOrder(int latitude,int longitude,int altitude,ulong time_usec) { - var msg = new mavlink_ping_t(); + var msg = new mavlink_gps_global_origin_t(); + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude = altitude; msg.time_usec = time_usec; - msg.seq = seq; - msg.target_system = target_system; - msg.target_component = target_component; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] //[FieldOffset(0)] - public ulong time_usec; + public int latitude; - /// PING sequence - [Units("")] - [Description("PING sequence")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] + //[FieldOffset(4)] + public int longitude; + + /// Altitude (MSL). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Positive for up.")] //[FieldOffset(8)] - public uint seq; + public int altitude; - /// 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system - [Units("")] - [Description("0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(12)] - public byte target_system; - - /// 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. - [Units("")] - [Description("0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.")] - //[FieldOffset(13)] - public byte target_component; + public ulong time_usec; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// Request to control this MAV - public struct mavlink_change_operator_control_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] + /// Bind a RC channel to a parameter. The parameter should change according to the RC channel value. + public struct mavlink_param_map_rc_t { /// packet ordered constructor - public mavlink_change_operator_control_t(byte target_system,byte control_request,byte version,byte[] passkey) + public mavlink_param_map_rc_t(float param_value0,float scale,float param_value_min,float param_value_max,short param_index,byte target_system,byte target_component,byte[] param_id,byte parameter_rc_channel_index) { + this.param_value0 = param_value0; + this.scale = scale; + this.param_value_min = param_value_min; + this.param_value_max = param_value_max; + this.param_index = param_index; this.target_system = target_system; - this.control_request = control_request; - this.version = version; - this.passkey = passkey; + this.target_component = target_component; + this.param_id = param_id; + this.parameter_rc_channel_index = parameter_rc_channel_index; } /// packet xml order - public static mavlink_change_operator_control_t PopulateXMLOrder(byte target_system,byte control_request,byte version,byte[] passkey) + public static mavlink_param_map_rc_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,short param_index,byte parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) { - var msg = new mavlink_change_operator_control_t(); + var msg = new mavlink_param_map_rc_t(); msg.target_system = target_system; - msg.control_request = control_request; - msg.version = version; - msg.passkey = passkey; + msg.target_component = target_component; + msg.param_id = param_id; + msg.param_index = param_index; + msg.parameter_rc_channel_index = parameter_rc_channel_index; + msg.param_value0 = param_value0; + msg.scale = scale; + msg.param_value_min = param_value_min; + msg.param_value_max = param_value_max; return msg; } - /// System the GCS requests control for + /// Initial parameter value [Units("")] - [Description("System the GCS requests control for")] + [Description("Initial parameter value")] //[FieldOffset(0)] + public float param_value0; + + /// Scale, maps the RC range [-1, 1] to a parameter value + [Units("")] + [Description("Scale, maps the RC range [-1, 1] to a parameter value")] + //[FieldOffset(4)] + public float scale; + + /// Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + [Units("")] + [Description("Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)")] + //[FieldOffset(8)] + public float param_value_min; + + /// Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + [Units("")] + [Description("Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)")] + //[FieldOffset(12)] + public float param_value_max; + + /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + [Units("")] + [Description("Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.")] + //[FieldOffset(16)] + public short param_index; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(18)] public byte target_system; - /// 0: request control of this MAV, 1: Release control of this MAV + /// Component ID [Units("")] - [Description("0: request control of this MAV, 1: Release control of this MAV")] - //[FieldOffset(1)] - public byte control_request; + [Description("Component ID")] + //[FieldOffset(19)] + public byte target_component; - /// 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. [rad] - [Units("[rad]")] - [Description("0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.")] - //[FieldOffset(2)] - public byte version; + /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + [Units("")] + [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; - /// Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and '!?,.-' + /// Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. [Units("")] - [Description("Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and '!?,.-'")] - //[FieldOffset(3)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=25)] - public byte[] passkey; + [Description("Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.")] + //[FieldOffset(36)] + public byte parameter_rc_channel_index; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Accept / deny control of this MAV - public struct mavlink_change_operator_control_ack_t + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html + public struct mavlink_mission_request_int_t { /// packet ordered constructor - public mavlink_change_operator_control_ack_t(byte gcs_system_id,byte control_request,byte ack) + public mavlink_mission_request_int_t(ushort seq,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) { - this.gcs_system_id = gcs_system_id; - this.control_request = control_request; - this.ack = ack; + this.seq = seq; + this.target_system = target_system; + this.target_component = target_component; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_change_operator_control_ack_t PopulateXMLOrder(byte gcs_system_id,byte control_request,byte ack) + public static mavlink_mission_request_int_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_change_operator_control_ack_t(); + var msg = new mavlink_mission_request_int_t(); - msg.gcs_system_id = gcs_system_id; - msg.control_request = control_request; - msg.ack = ack; + msg.target_system = target_system; + msg.target_component = target_component; + msg.seq = seq; + msg.mission_type = mission_type; return msg; } - /// ID of the GCS this message + /// Sequence [Units("")] - [Description("ID of the GCS this message ")] + [Description("Sequence")] //[FieldOffset(0)] - public byte gcs_system_id; + public ushort seq; - /// 0: request control of this MAV, 1: Release control of this MAV + /// System ID [Units("")] - [Description("0: request control of this MAV, 1: Release control of this MAV")] - //[FieldOffset(1)] - public byte control_request; + [Description("System ID")] + //[FieldOffset(2)] + public byte target_system; - /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + /// Component ID [Units("")] - [Description("0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control")] - //[FieldOffset(2)] - public byte ack; + [Description("Component ID")] + //[FieldOffset(3)] + public byte target_component; + + /// Mission type. MAV_MISSION_TYPE + [Units("")] + [Description("Mission type.")] + //[FieldOffset(4)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - /// Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. - public struct mavlink_auth_key_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)] + /// Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. + public struct mavlink_safety_set_allowed_area_t { /// packet ordered constructor - public mavlink_auth_key_t(byte[] key) + public mavlink_safety_set_allowed_area_t(float p1x,float p1y,float p1z,float p2x,float p2y,float p2z,byte target_system,byte target_component,/*MAV_FRAME*/byte frame) { - this.key = key; + this.p1x = p1x; + this.p1y = p1y; + this.p1z = p1z; + this.p2x = p2x; + this.p2y = p2y; + this.p2z = p2z; + this.target_system = target_system; + this.target_component = target_component; + this.frame = frame; } /// packet xml order - public static mavlink_auth_key_t PopulateXMLOrder(byte[] key) + public static mavlink_safety_set_allowed_area_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_FRAME*/byte frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) { - var msg = new mavlink_auth_key_t(); + var msg = new mavlink_safety_set_allowed_area_t(); - msg.key = key; + msg.target_system = target_system; + msg.target_component = target_component; + msg.frame = frame; + msg.p1x = p1x; + msg.p1y = p1y; + msg.p1z = p1z; + msg.p2x = p2x; + msg.p2y = p2y; + msg.p2z = p2z; return msg; } - /// key - [Units("")] - [Description("key")] + /// x position 1 / Latitude 1 [m] + [Units("[m]")] + [Description("x position 1 / Latitude 1")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] key; + public float p1x; + + /// y position 1 / Longitude 1 [m] + [Units("[m]")] + [Description("y position 1 / Longitude 1")] + //[FieldOffset(4)] + public float p1y; + + /// z position 1 / Altitude 1 [m] + [Units("[m]")] + [Description("z position 1 / Altitude 1")] + //[FieldOffset(8)] + public float p1z; + + /// x position 2 / Latitude 2 [m] + [Units("[m]")] + [Description("x position 2 / Latitude 2")] + //[FieldOffset(12)] + public float p2x; + + /// y position 2 / Longitude 2 [m] + [Units("[m]")] + [Description("y position 2 / Longitude 2")] + //[FieldOffset(16)] + public float p2y; + + /// z position 2 / Altitude 2 [m] + [Units("[m]")] + [Description("z position 2 / Altitude 2")] + //[FieldOffset(20)] + public float p2z; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(24)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(25)] + public byte target_component; + + /// Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. MAV_FRAME + [Units("")] + [Description("Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.")] + //[FieldOffset(26)] + public /*MAV_FRAME*/byte frame; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. - public struct mavlink_set_mode_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)] + /// Read out the safety zone the MAV currently assumes. + public struct mavlink_safety_allowed_area_t { /// packet ordered constructor - public mavlink_set_mode_t(uint custom_mode,byte target_system,/*MAV_MODE*/byte base_mode) + public mavlink_safety_allowed_area_t(float p1x,float p1y,float p1z,float p2x,float p2y,float p2z,/*MAV_FRAME*/byte frame) { - this.custom_mode = custom_mode; - this.target_system = target_system; - this.base_mode = base_mode; + this.p1x = p1x; + this.p1y = p1y; + this.p1z = p1z; + this.p2x = p2x; + this.p2y = p2y; + this.p2z = p2z; + this.frame = frame; } /// packet xml order - public static mavlink_set_mode_t PopulateXMLOrder(byte target_system,/*MAV_MODE*/byte base_mode,uint custom_mode) + public static mavlink_safety_allowed_area_t PopulateXMLOrder(/*MAV_FRAME*/byte frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) { - var msg = new mavlink_set_mode_t(); + var msg = new mavlink_safety_allowed_area_t(); - msg.target_system = target_system; - msg.base_mode = base_mode; - msg.custom_mode = custom_mode; + msg.frame = frame; + msg.p1x = p1x; + msg.p1y = p1y; + msg.p1z = p1z; + msg.p2x = p2x; + msg.p2y = p2y; + msg.p2z = p2z; return msg; } - /// The new autopilot-specific mode. This field can be ignored by an autopilot. - [Units("")] - [Description("The new autopilot-specific mode. This field can be ignored by an autopilot.")] + /// x position 1 / Latitude 1 [m] + [Units("[m]")] + [Description("x position 1 / Latitude 1")] //[FieldOffset(0)] - public uint custom_mode; + public float p1x; - /// The system setting the mode - [Units("")] - [Description("The system setting the mode")] + /// y position 1 / Longitude 1 [m] + [Units("[m]")] + [Description("y position 1 / Longitude 1")] //[FieldOffset(4)] - public byte target_system; + public float p1y; - /// The new base mode. MAV_MODE + /// z position 1 / Altitude 1 [m] + [Units("[m]")] + [Description("z position 1 / Altitude 1")] + //[FieldOffset(8)] + public float p1z; + + /// x position 2 / Latitude 2 [m] + [Units("[m]")] + [Description("x position 2 / Latitude 2")] + //[FieldOffset(12)] + public float p2x; + + /// y position 2 / Longitude 2 [m] + [Units("[m]")] + [Description("y position 2 / Longitude 2")] + //[FieldOffset(16)] + public float p2y; + + /// z position 2 / Altitude 2 [m] + [Units("[m]")] + [Description("z position 2 / Altitude 2")] + //[FieldOffset(20)] + public float p2z; + + /// Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. MAV_FRAME [Units("")] - [Description("The new base mode.")] - //[FieldOffset(5)] - public /*MAV_MODE*/byte base_mode; + [Description("Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.")] + //[FieldOffset(24)] + public /*MAV_FRAME*/byte frame; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code. - public struct mavlink_param_request_read_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=72)] + /// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + public struct mavlink_attitude_quaternion_cov_t { /// packet ordered constructor - public mavlink_param_request_read_t(short param_index,byte target_system,byte target_component,byte[] param_id) + public mavlink_attitude_quaternion_cov_t(ulong time_usec,float[] q,float rollspeed,float pitchspeed,float yawspeed,float[] covariance) { - this.param_index = param_index; - this.target_system = target_system; - this.target_component = target_component; - this.param_id = param_id; + this.time_usec = time_usec; + this.q = q; + this.rollspeed = rollspeed; + this.pitchspeed = pitchspeed; + this.yawspeed = yawspeed; + this.covariance = covariance; } /// packet xml order - public static mavlink_param_request_read_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,short param_index) + public static mavlink_attitude_quaternion_cov_t PopulateXMLOrder(ulong time_usec,float[] q,float rollspeed,float pitchspeed,float yawspeed,float[] covariance) { - var msg = new mavlink_param_request_read_t(); + var msg = new mavlink_attitude_quaternion_cov_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.param_id = param_id; - msg.param_index = param_index; + msg.time_usec = time_usec; + msg.q = q; + msg.rollspeed = rollspeed; + msg.pitchspeed = pitchspeed; + msg.yawspeed = yawspeed; + msg.covariance = covariance; return msg; } - /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - [Units("")] - [Description("Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public short param_index; + public ulong time_usec; - /// System ID + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) [Units("")] - [Description("System ID")] - //[FieldOffset(2)] - public byte target_system; + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; + + /// Roll angular speed [rad/s] + [Units("[rad/s]")] + [Description("Roll angular speed")] + //[FieldOffset(24)] + public float rollspeed; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(3)] - public byte target_component; + /// Pitch angular speed [rad/s] + [Units("[rad/s]")] + [Description("Pitch angular speed")] + //[FieldOffset(28)] + public float pitchspeed; - /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Yaw angular speed [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular speed")] + //[FieldOffset(32)] + public float yawspeed; + + /// Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [Description("Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(36)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] + public float[] covariance; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html - public struct mavlink_param_request_list_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] + /// The state of the fixed wing navigation and position controller. + public struct mavlink_nav_controller_output_t { /// packet ordered constructor - public mavlink_param_request_list_t(byte target_system,byte target_component) + public mavlink_nav_controller_output_t(float nav_roll,float nav_pitch,float alt_error,float aspd_error,float xtrack_error,short nav_bearing,short target_bearing,ushort wp_dist) { - this.target_system = target_system; - this.target_component = target_component; + this.nav_roll = nav_roll; + this.nav_pitch = nav_pitch; + this.alt_error = alt_error; + this.aspd_error = aspd_error; + this.xtrack_error = xtrack_error; + this.nav_bearing = nav_bearing; + this.target_bearing = target_bearing; + this.wp_dist = wp_dist; } /// packet xml order - public static mavlink_param_request_list_t PopulateXMLOrder(byte target_system,byte target_component) + public static mavlink_nav_controller_output_t PopulateXMLOrder(float nav_roll,float nav_pitch,short nav_bearing,short target_bearing,ushort wp_dist,float alt_error,float aspd_error,float xtrack_error) { - var msg = new mavlink_param_request_list_t(); + var msg = new mavlink_nav_controller_output_t(); - msg.target_system = target_system; - msg.target_component = target_component; + msg.nav_roll = nav_roll; + msg.nav_pitch = nav_pitch; + msg.nav_bearing = nav_bearing; + msg.target_bearing = target_bearing; + msg.wp_dist = wp_dist; + msg.alt_error = alt_error; + msg.aspd_error = aspd_error; + msg.xtrack_error = xtrack_error; return msg; } - /// System ID - [Units("")] - [Description("System ID")] + /// Current desired roll [deg] + [Units("[deg]")] + [Description("Current desired roll")] //[FieldOffset(0)] - public byte target_system; + public float nav_roll; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + /// Current desired pitch [deg] + [Units("[deg]")] + [Description("Current desired pitch")] + //[FieldOffset(4)] + public float nav_pitch; + + /// Current altitude error [m] + [Units("[m]")] + [Description("Current altitude error")] + //[FieldOffset(8)] + public float alt_error; + + /// Current airspeed error [m/s] + [Units("[m/s]")] + [Description("Current airspeed error")] + //[FieldOffset(12)] + public float aspd_error; + + /// Current crosstrack error on x-y plane [m] + [Units("[m]")] + [Description("Current crosstrack error on x-y plane")] + //[FieldOffset(16)] + public float xtrack_error; + + /// Current desired heading [deg] + [Units("[deg]")] + [Description("Current desired heading")] + //[FieldOffset(20)] + public short nav_bearing; + + /// Bearing to current waypoint/target [deg] + [Units("[deg]")] + [Description("Bearing to current waypoint/target")] + //[FieldOffset(22)] + public short target_bearing; + + /// Distance to active waypoint [m] + [Units("[m]")] + [Description("Distance to active waypoint")] + //[FieldOffset(24)] + public ushort wp_dist; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)] - /// Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html - public struct mavlink_param_value_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=181)] + /// The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. + public struct mavlink_global_position_int_cov_t { /// packet ordered constructor - public mavlink_param_value_t(float param_value,ushort param_count,ushort param_index,byte[] param_id,/*MAV_PARAM_TYPE*/byte param_type) + public mavlink_global_position_int_cov_t(ulong time_usec,int lat,int lon,int alt,int relative_alt,float vx,float vy,float vz,float[] covariance,/*MAV_ESTIMATOR_TYPE*/byte estimator_type) { - this.param_value = param_value; - this.param_count = param_count; - this.param_index = param_index; - this.param_id = param_id; - this.param_type = param_type; + this.time_usec = time_usec; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.relative_alt = relative_alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.covariance = covariance; + this.estimator_type = estimator_type; } /// packet xml order - public static mavlink_param_value_t PopulateXMLOrder(byte[] param_id,float param_value,/*MAV_PARAM_TYPE*/byte param_type,ushort param_count,ushort param_index) + public static mavlink_global_position_int_cov_t PopulateXMLOrder(ulong time_usec,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,int lat,int lon,int alt,int relative_alt,float vx,float vy,float vz,float[] covariance) { - var msg = new mavlink_param_value_t(); + var msg = new mavlink_global_position_int_cov_t(); - msg.param_id = param_id; - msg.param_value = param_value; - msg.param_type = param_type; - msg.param_count = param_count; - msg.param_index = param_index; + msg.time_usec = time_usec; + msg.estimator_type = estimator_type; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.relative_alt = relative_alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.covariance = covariance; return msg; } - /// Onboard parameter value - [Units("")] - [Description("Onboard parameter value")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public float param_value; + public ulong time_usec; - /// Total number of onboard parameters - [Units("")] - [Description("Total number of onboard parameters")] - //[FieldOffset(4)] - public ushort param_count; + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] + //[FieldOffset(8)] + public int lat; - /// Index of this onboard parameter - [Units("")] - [Description("Index of this onboard parameter")] - //[FieldOffset(6)] - public ushort param_index; + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] + //[FieldOffset(12)] + public int lon; - /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Altitude in meters above MSL [mm] + [Units("[mm]")] + [Description("Altitude in meters above MSL")] + //[FieldOffset(16)] + public int alt; + + /// Altitude above ground [mm] + [Units("[mm]")] + [Description("Altitude above ground")] + //[FieldOffset(20)] + public int relative_alt; + + /// Ground X Speed (Latitude) [m/s] + [Units("[m/s]")] + [Description("Ground X Speed (Latitude)")] + //[FieldOffset(24)] + public float vx; + + /// Ground Y Speed (Longitude) [m/s] + [Units("[m/s]")] + [Description("Ground Y Speed (Longitude)")] + //[FieldOffset(28)] + public float vy; + + /// Ground Z Speed (Altitude) [m/s] + [Units("[m/s]")] + [Description("Ground Z Speed (Altitude)")] + //[FieldOffset(32)] + public float vz; + + /// Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [Description("Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(36)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=36)] + public float[] covariance; - /// Onboard parameter type. MAV_PARAM_TYPE + /// Class id of the estimator this estimate originated from. MAV_ESTIMATOR_TYPE [Units("")] - [Description("Onboard parameter type.")] - //[FieldOffset(24)] - public /*MAV_PARAM_TYPE*/byte param_type; + [Description("Class id of the estimator this estimate originated from.")] + //[FieldOffset(180)] + public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] - /// Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. - public struct mavlink_param_set_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=225)] + /// The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + public struct mavlink_local_position_ned_cov_t { /// packet ordered constructor - public mavlink_param_set_t(float param_value,byte target_system,byte target_component,byte[] param_id,/*MAV_PARAM_TYPE*/byte param_type) + public mavlink_local_position_ned_cov_t(ulong time_usec,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,float[] covariance,/*MAV_ESTIMATOR_TYPE*/byte estimator_type) { - this.param_value = param_value; - this.target_system = target_system; - this.target_component = target_component; - this.param_id = param_id; - this.param_type = param_type; + this.time_usec = time_usec; + this.x = x; + this.y = y; + this.z = z; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.ax = ax; + this.ay = ay; + this.az = az; + this.covariance = covariance; + this.estimator_type = estimator_type; } /// packet xml order - public static mavlink_param_set_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,float param_value,/*MAV_PARAM_TYPE*/byte param_type) + public static mavlink_local_position_ned_cov_t PopulateXMLOrder(ulong time_usec,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,float[] covariance) { - var msg = new mavlink_param_set_t(); + var msg = new mavlink_local_position_ned_cov_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.param_id = param_id; - msg.param_value = param_value; - msg.param_type = param_type; + msg.time_usec = time_usec; + msg.estimator_type = estimator_type; + msg.x = x; + msg.y = y; + msg.z = z; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.ax = ax; + msg.ay = ay; + msg.az = az; + msg.covariance = covariance; return msg; } - /// Onboard parameter value - [Units("")] - [Description("Onboard parameter value")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public float param_value; + public ulong time_usec; - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(4)] - public byte target_system; + /// X Position [m] + [Units("[m]")] + [Description("X Position")] + //[FieldOffset(8)] + public float x; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(5)] - public byte target_component; + /// Y Position [m] + [Units("[m]")] + [Description("Y Position")] + //[FieldOffset(12)] + public float y; - /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Z Position [m] + [Units("[m]")] + [Description("Z Position")] + //[FieldOffset(16)] + public float z; + + /// X Speed [m/s] + [Units("[m/s]")] + [Description("X Speed")] + //[FieldOffset(20)] + public float vx; + + /// Y Speed [m/s] + [Units("[m/s]")] + [Description("Y Speed")] + //[FieldOffset(24)] + public float vy; + + /// Z Speed [m/s] + [Units("[m/s]")] + [Description("Z Speed")] + //[FieldOffset(28)] + public float vz; + + /// X Acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("X Acceleration")] + //[FieldOffset(32)] + public float ax; + + /// Y Acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Y Acceleration")] + //[FieldOffset(36)] + public float ay; + + /// Z Acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Z Acceleration")] + //[FieldOffset(40)] + public float az; + + /// Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [Description("Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(44)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=45)] + public float[] covariance; - /// Onboard parameter type. MAV_PARAM_TYPE + /// Class id of the estimator this estimate originated from. MAV_ESTIMATOR_TYPE [Units("")] - [Description("Onboard parameter type.")] - //[FieldOffset(22)] - public /*MAV_PARAM_TYPE*/byte param_type; + [Description("Class id of the estimator this estimate originated from.")] + //[FieldOffset(224)] + public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] - /// The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. - public struct mavlink_gps_raw_int_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification. + public struct mavlink_rc_channels_t { /// packet ordered constructor - public mavlink_gps_raw_int_t(ulong time_usec,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,/*GPS_FIX_TYPE*/byte fix_type,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw) + public mavlink_rc_channels_t(uint time_boot_ms,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw,byte chancount,byte rssi) { - this.time_usec = time_usec; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.eph = eph; - this.epv = epv; - this.vel = vel; - this.cog = cog; - this.fix_type = fix_type; - this.satellites_visible = satellites_visible; - this.alt_ellipsoid = alt_ellipsoid; - this.h_acc = h_acc; - this.v_acc = v_acc; - this.vel_acc = vel_acc; - this.hdg_acc = hdg_acc; - this.yaw = yaw; + this.time_boot_ms = time_boot_ms; + this.chan1_raw = chan1_raw; + this.chan2_raw = chan2_raw; + this.chan3_raw = chan3_raw; + this.chan4_raw = chan4_raw; + this.chan5_raw = chan5_raw; + this.chan6_raw = chan6_raw; + this.chan7_raw = chan7_raw; + this.chan8_raw = chan8_raw; + this.chan9_raw = chan9_raw; + this.chan10_raw = chan10_raw; + this.chan11_raw = chan11_raw; + this.chan12_raw = chan12_raw; + this.chan13_raw = chan13_raw; + this.chan14_raw = chan14_raw; + this.chan15_raw = chan15_raw; + this.chan16_raw = chan16_raw; + this.chan17_raw = chan17_raw; + this.chan18_raw = chan18_raw; + this.chancount = chancount; + this.rssi = rssi; } /// packet xml order - public static mavlink_gps_raw_int_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_TYPE*/byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw) + public static mavlink_rc_channels_t PopulateXMLOrder(uint time_boot_ms,byte chancount,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw,byte rssi) { - var msg = new mavlink_gps_raw_int_t(); + var msg = new mavlink_rc_channels_t(); - msg.time_usec = time_usec; - msg.fix_type = fix_type; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.eph = eph; - msg.epv = epv; - msg.vel = vel; - msg.cog = cog; - msg.satellites_visible = satellites_visible; - msg.alt_ellipsoid = alt_ellipsoid; - msg.h_acc = h_acc; - msg.v_acc = v_acc; - msg.vel_acc = vel_acc; - msg.hdg_acc = hdg_acc; - msg.yaw = yaw; + msg.time_boot_ms = time_boot_ms; + msg.chancount = chancount; + msg.chan1_raw = chan1_raw; + msg.chan2_raw = chan2_raw; + msg.chan3_raw = chan3_raw; + msg.chan4_raw = chan4_raw; + msg.chan5_raw = chan5_raw; + msg.chan6_raw = chan6_raw; + msg.chan7_raw = chan7_raw; + msg.chan8_raw = chan8_raw; + msg.chan9_raw = chan9_raw; + msg.chan10_raw = chan10_raw; + msg.chan11_raw = chan11_raw; + msg.chan12_raw = chan12_raw; + msg.chan13_raw = chan13_raw; + msg.chan14_raw = chan14_raw; + msg.chan15_raw = chan15_raw; + msg.chan16_raw = chan16_raw; + msg.chan17_raw = chan17_raw; + msg.chan18_raw = chan18_raw; + msg.rssi = rssi; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// Latitude (WGS84, EGM96 ellipsoid) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84, EGM96 ellipsoid)")] + /// RC channel 1 value. [us] + [Units("[us]")] + [Description("RC channel 1 value.")] + //[FieldOffset(4)] + public ushort chan1_raw; + + /// RC channel 2 value. [us] + [Units("[us]")] + [Description("RC channel 2 value.")] + //[FieldOffset(6)] + public ushort chan2_raw; + + /// RC channel 3 value. [us] + [Units("[us]")] + [Description("RC channel 3 value.")] //[FieldOffset(8)] - public int lat; + public ushort chan3_raw; - /// Longitude (WGS84, EGM96 ellipsoid) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84, EGM96 ellipsoid)")] + /// RC channel 4 value. [us] + [Units("[us]")] + [Description("RC channel 4 value.")] + //[FieldOffset(10)] + public ushort chan4_raw; + + /// RC channel 5 value. [us] + [Units("[us]")] + [Description("RC channel 5 value.")] //[FieldOffset(12)] - public int lon; + public ushort chan5_raw; - /// Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.")] + /// RC channel 6 value. [us] + [Units("[us]")] + [Description("RC channel 6 value.")] + //[FieldOffset(14)] + public ushort chan6_raw; + + /// RC channel 7 value. [us] + [Units("[us]")] + [Description("RC channel 7 value.")] //[FieldOffset(16)] - public int alt; + public ushort chan7_raw; + + /// RC channel 8 value. [us] + [Units("[us]")] + [Description("RC channel 8 value.")] + //[FieldOffset(18)] + public ushort chan8_raw; - /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - [Units("")] - [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] + /// RC channel 9 value. [us] + [Units("[us]")] + [Description("RC channel 9 value.")] //[FieldOffset(20)] - public ushort eph; + public ushort chan9_raw; - /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - [Units("")] - [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + /// RC channel 10 value. [us] + [Units("[us]")] + [Description("RC channel 10 value.")] //[FieldOffset(22)] - public ushort epv; + public ushort chan10_raw; - /// GPS ground speed. If unknown, set to: UINT16_MAX [cm/s] - [Units("[cm/s]")] - [Description("GPS ground speed. If unknown, set to: UINT16_MAX")] + /// RC channel 11 value. [us] + [Units("[us]")] + [Description("RC channel 11 value.")] //[FieldOffset(24)] - public ushort vel; + public ushort chan11_raw; - /// Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX [cdeg] - [Units("[cdeg]")] - [Description("Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX")] + /// RC channel 12 value. [us] + [Units("[us]")] + [Description("RC channel 12 value.")] //[FieldOffset(26)] - public ushort cog; + public ushort chan12_raw; - /// GPS fix type. GPS_FIX_TYPE - [Units("")] - [Description("GPS fix type.")] + /// RC channel 13 value. [us] + [Units("[us]")] + [Description("RC channel 13 value.")] //[FieldOffset(28)] - public /*GPS_FIX_TYPE*/byte fix_type; - - /// Number of satellites visible. If unknown, set to 255 - [Units("")] - [Description("Number of satellites visible. If unknown, set to 255")] - //[FieldOffset(29)] - public byte satellites_visible; + public ushort chan13_raw; - /// Altitude (above WGS84, EGM96 ellipsoid). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (above WGS84, EGM96 ellipsoid). Positive for up.")] + /// RC channel 14 value. [us] + [Units("[us]")] + [Description("RC channel 14 value.")] //[FieldOffset(30)] - public int alt_ellipsoid; + public ushort chan14_raw; - /// Position uncertainty. [mm] - [Units("[mm]")] - [Description("Position uncertainty.")] + /// RC channel 15 value. [us] + [Units("[us]")] + [Description("RC channel 15 value.")] + //[FieldOffset(32)] + public ushort chan15_raw; + + /// RC channel 16 value. [us] + [Units("[us]")] + [Description("RC channel 16 value.")] //[FieldOffset(34)] - public uint h_acc; + public ushort chan16_raw; - /// Altitude uncertainty. [mm] - [Units("[mm]")] - [Description("Altitude uncertainty.")] - //[FieldOffset(38)] - public uint v_acc; + /// RC channel 17 value. [us] + [Units("[us]")] + [Description("RC channel 17 value.")] + //[FieldOffset(36)] + public ushort chan17_raw; - /// Speed uncertainty. [mm] - [Units("[mm]")] - [Description("Speed uncertainty.")] - //[FieldOffset(42)] - public uint vel_acc; + /// RC channel 18 value. [us] + [Units("[us]")] + [Description("RC channel 18 value.")] + //[FieldOffset(38)] + public ushort chan18_raw; - /// Heading / track uncertainty [degE5] - [Units("[degE5]")] - [Description("Heading / track uncertainty")] - //[FieldOffset(46)] - public uint hdg_acc; + /// Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + [Units("")] + [Description("Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.")] + //[FieldOffset(40)] + public byte chancount; - /// Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. [cdeg] - [Units("[cdeg]")] - [Description("Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.")] - //[FieldOffset(50)] - public ushort yaw; + /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + [Units("")] + [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(41)] + public byte rssi; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=101)] - /// The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. - public struct mavlink_gps_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Request a data stream. + public struct mavlink_request_data_stream_t { /// packet ordered constructor - public mavlink_gps_status_t(byte satellites_visible,byte[] satellite_prn,byte[] satellite_used,byte[] satellite_elevation,byte[] satellite_azimuth,byte[] satellite_snr) + public mavlink_request_data_stream_t(ushort req_message_rate,byte target_system,byte target_component,byte req_stream_id,byte start_stop) { - this.satellites_visible = satellites_visible; - this.satellite_prn = satellite_prn; - this.satellite_used = satellite_used; - this.satellite_elevation = satellite_elevation; - this.satellite_azimuth = satellite_azimuth; - this.satellite_snr = satellite_snr; + this.req_message_rate = req_message_rate; + this.target_system = target_system; + this.target_component = target_component; + this.req_stream_id = req_stream_id; + this.start_stop = start_stop; } /// packet xml order - public static mavlink_gps_status_t PopulateXMLOrder(byte satellites_visible,byte[] satellite_prn,byte[] satellite_used,byte[] satellite_elevation,byte[] satellite_azimuth,byte[] satellite_snr) + public static mavlink_request_data_stream_t PopulateXMLOrder(byte target_system,byte target_component,byte req_stream_id,ushort req_message_rate,byte start_stop) { - var msg = new mavlink_gps_status_t(); + var msg = new mavlink_request_data_stream_t(); - msg.satellites_visible = satellites_visible; - msg.satellite_prn = satellite_prn; - msg.satellite_used = satellite_used; - msg.satellite_elevation = satellite_elevation; - msg.satellite_azimuth = satellite_azimuth; - msg.satellite_snr = satellite_snr; + msg.target_system = target_system; + msg.target_component = target_component; + msg.req_stream_id = req_stream_id; + msg.req_message_rate = req_message_rate; + msg.start_stop = start_stop; return msg; } - /// Number of satellites visible - [Units("")] - [Description("Number of satellites visible")] + /// The requested message rate [Hz] + [Units("[Hz]")] + [Description("The requested message rate")] //[FieldOffset(0)] - public byte satellites_visible; + public ushort req_message_rate; - /// Global satellite ID + /// The target requested to send the message stream. [Units("")] - [Description("Global satellite ID")] - //[FieldOffset(1)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_prn; + [Description("The target requested to send the message stream.")] + //[FieldOffset(2)] + public byte target_system; - /// 0: Satellite not used, 1: used for localization + /// The target requested to send the message stream. [Units("")] - [Description("0: Satellite not used, 1: used for localization")] - //[FieldOffset(21)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_used; - - /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite [deg] - [Units("[deg]")] - [Description("Elevation (0: right on top of receiver, 90: on the horizon) of satellite")] - //[FieldOffset(41)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_elevation; + [Description("The target requested to send the message stream.")] + //[FieldOffset(3)] + public byte target_component; - /// Direction of satellite, 0: 0 deg, 255: 360 deg. [deg] - [Units("[deg]")] - [Description("Direction of satellite, 0: 0 deg, 255: 360 deg.")] - //[FieldOffset(61)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_azimuth; + /// The ID of the requested data stream + [Units("")] + [Description("The ID of the requested data stream")] + //[FieldOffset(4)] + public byte req_stream_id; - /// Signal to noise ratio of satellite [dB] - [Units("[dB]")] - [Description("Signal to noise ratio of satellite")] - //[FieldOffset(81)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_snr; + /// 1 to start sending, 0 to stop sending. + [Units("")] + [Description("1 to start sending, 0 to stop sending.")] + //[FieldOffset(5)] + public byte start_stop; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] - /// The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units - public struct mavlink_scaled_imu_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// Data stream status information. + public struct mavlink_data_stream_t { /// packet ordered constructor - public mavlink_scaled_imu_t(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) + public mavlink_data_stream_t(ushort message_rate,byte stream_id,byte on_off) { - this.time_boot_ms = time_boot_ms; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.xmag = xmag; - this.ymag = ymag; - this.zmag = zmag; - this.temperature = temperature; + this.message_rate = message_rate; + this.stream_id = stream_id; + this.on_off = on_off; } /// packet xml order - public static mavlink_scaled_imu_t PopulateXMLOrder(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) + public static mavlink_data_stream_t PopulateXMLOrder(byte stream_id,ushort message_rate,byte on_off) { - var msg = new mavlink_scaled_imu_t(); + var msg = new mavlink_data_stream_t(); - msg.time_boot_ms = time_boot_ms; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.xmag = xmag; - msg.ymag = ymag; - msg.zmag = zmag; - msg.temperature = temperature; + msg.stream_id = stream_id; + msg.message_rate = message_rate; + msg.on_off = on_off; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// The message rate [Hz] + [Units("[Hz]")] + [Description("The message rate")] //[FieldOffset(0)] - public uint time_boot_ms; - - /// X acceleration [mG] - [Units("[mG]")] - [Description("X acceleration")] - //[FieldOffset(4)] - public short xacc; - - /// Y acceleration [mG] - [Units("[mG]")] - [Description("Y acceleration")] - //[FieldOffset(6)] - public short yacc; - - /// Z acceleration [mG] - [Units("[mG]")] - [Description("Z acceleration")] - //[FieldOffset(8)] - public short zacc; - - /// Angular speed around X axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around X axis")] - //[FieldOffset(10)] - public short xgyro; - - /// Angular speed around Y axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around Y axis")] - //[FieldOffset(12)] - public short ygyro; - - /// Angular speed around Z axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around Z axis")] - //[FieldOffset(14)] - public short zgyro; - - /// X Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("X Magnetic field")] - //[FieldOffset(16)] - public short xmag; - - /// Y Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("Y Magnetic field")] - //[FieldOffset(18)] - public short ymag; + public ushort message_rate; - /// Z Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("Z Magnetic field")] - //[FieldOffset(20)] - public short zmag; + /// The ID of the requested data stream + [Units("")] + [Description("The ID of the requested data stream")] + //[FieldOffset(2)] + public byte stream_id; - /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] - [Units("[cdegC]")] - [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] - //[FieldOffset(22)] - public short temperature; + /// 1 stream is enabled, 0 stream is stopped. + [Units("")] + [Description("1 stream is enabled, 0 stream is stopped.")] + //[FieldOffset(3)] + public byte on_off; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=29)] - /// The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging. - public struct mavlink_raw_imu_t + /// 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_raw_imu_t(ulong time_usec,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,byte id,short temperature) + 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.time_usec = time_usec; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.xmag = xmag; - this.ymag = ymag; - this.zmag = zmag; - this.id = id; - this.temperature = temperature; + this.x = x; + this.y = y; + this.z = z; + 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_raw_imu_t PopulateXMLOrder(ulong time_usec,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,byte id,short temperature) + 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_raw_imu_t(); + var msg = new mavlink_manual_control_t(); - msg.time_usec = time_usec; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.xmag = xmag; - msg.ymag = ymag; - msg.zmag = zmag; - msg.id = id; - msg.temperature = temperature; + msg.target = target; + msg.x = x; + msg.y = y; + 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; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(0)] - public ulong time_usec; - - /// X acceleration (raw) + /// X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. [Units("")] - [Description("X acceleration (raw)")] - //[FieldOffset(8)] - public short xacc; + [Description("X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.")] + //[FieldOffset(0)] + public short x; - /// Y acceleration (raw) + /// Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. [Units("")] - [Description("Y acceleration (raw)")] - //[FieldOffset(10)] - public short yacc; + [Description("Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.")] + //[FieldOffset(2)] + public short y; - /// Z acceleration (raw) + /// 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. [Units("")] - [Description("Z acceleration (raw)")] - //[FieldOffset(12)] - public short zacc; + [Description("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.")] + //[FieldOffset(4)] + public short z; - /// Angular speed around X axis (raw) + /// 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. [Units("")] - [Description("Angular speed around X axis (raw)")] - //[FieldOffset(14)] - public short xgyro; + [Description("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.")] + //[FieldOffset(6)] + public short r; - /// Angular speed around Y axis (raw) + /// A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. [Units("")] - [Description("Angular speed around Y axis (raw)")] - //[FieldOffset(16)] - public short ygyro; + [Description("A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.")] + //[FieldOffset(8)] + public ushort buttons; - /// Angular speed around Z axis (raw) + /// The system to be controlled. [Units("")] - [Description("Angular speed around Z axis (raw)")] - //[FieldOffset(18)] - public short zgyro; + [Description("The system to be controlled.")] + //[FieldOffset(10)] + public byte target; - /// X Magnetic field (raw) + /// 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("X Magnetic field (raw)")] - //[FieldOffset(20)] - public short xmag; + [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; - /// Y Magnetic field (raw) + /// 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("Y Magnetic field (raw)")] - //[FieldOffset(22)] - public short ymag; + [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; - /// Z Magnetic field (raw) + /// 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("Z Magnetic field (raw)")] - //[FieldOffset(24)] - public short zmag; + [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; - /// Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) + /// 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("Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)")] - //[FieldOffset(26)] - public byte id; - - /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] - [Units("[cdegC]")] - [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] - //[FieldOffset(27)] - public short temperature; - }; - - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. - public struct mavlink_raw_pressure_t - { - /// packet ordered constructor - public mavlink_raw_pressure_t(ulong time_usec,short press_abs,short press_diff1,short press_diff2,short temperature) - { - this.time_usec = time_usec; - this.press_abs = press_abs; - this.press_diff1 = press_diff1; - this.press_diff2 = press_diff2; - this.temperature = temperature; - - } - - /// packet xml order - public static mavlink_raw_pressure_t PopulateXMLOrder(ulong time_usec,short press_abs,short press_diff1,short press_diff2,short temperature) - { - var msg = new mavlink_raw_pressure_t(); - - msg.time_usec = time_usec; - msg.press_abs = press_abs; - msg.press_diff1 = press_diff1; - msg.press_diff2 = press_diff2; - msg.temperature = temperature; - - return msg; - } - + [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; - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(0)] - public ulong time_usec; + /// 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; - /// Absolute pressure (raw) + /// 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("Absolute pressure (raw)")] - //[FieldOffset(8)] - public short press_abs; + [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; - /// Differential pressure 1 (raw, 0 if nonexistent) + /// 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("Differential pressure 1 (raw, 0 if nonexistent)")] - //[FieldOffset(10)] - public short press_diff1; + [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; - /// Differential pressure 2 (raw, 0 if nonexistent) + /// 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("Differential pressure 2 (raw, 0 if nonexistent)")] - //[FieldOffset(12)] - public short press_diff2; + [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; - /// Raw Temperature measurement (raw) + /// 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("Raw Temperature measurement (raw)")] - //[FieldOffset(14)] - public short temperature; + [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; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. - public struct mavlink_scaled_pressure_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] + /// 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 + public struct mavlink_rc_channels_override_t { /// packet ordered constructor - public mavlink_scaled_pressure_t(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) + public mavlink_rc_channels_override_t(ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,byte target_system,byte target_component,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw) { - this.time_boot_ms = time_boot_ms; - this.press_abs = press_abs; - this.press_diff = press_diff; - this.temperature = temperature; - this.temperature_press_diff = temperature_press_diff; + this.chan1_raw = chan1_raw; + this.chan2_raw = chan2_raw; + this.chan3_raw = chan3_raw; + this.chan4_raw = chan4_raw; + this.chan5_raw = chan5_raw; + this.chan6_raw = chan6_raw; + this.chan7_raw = chan7_raw; + this.chan8_raw = chan8_raw; + this.target_system = target_system; + this.target_component = target_component; + this.chan9_raw = chan9_raw; + this.chan10_raw = chan10_raw; + this.chan11_raw = chan11_raw; + this.chan12_raw = chan12_raw; + this.chan13_raw = chan13_raw; + this.chan14_raw = chan14_raw; + this.chan15_raw = chan15_raw; + this.chan16_raw = chan16_raw; + this.chan17_raw = chan17_raw; + this.chan18_raw = chan18_raw; } /// packet xml order - public static mavlink_scaled_pressure_t PopulateXMLOrder(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) + public static mavlink_rc_channels_override_t PopulateXMLOrder(byte target_system,byte target_component,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw) { - var msg = new mavlink_scaled_pressure_t(); + var msg = new mavlink_rc_channels_override_t(); - msg.time_boot_ms = time_boot_ms; - msg.press_abs = press_abs; - msg.press_diff = press_diff; - msg.temperature = temperature; - msg.temperature_press_diff = temperature_press_diff; + msg.target_system = target_system; + msg.target_component = target_component; + msg.chan1_raw = chan1_raw; + msg.chan2_raw = chan2_raw; + msg.chan3_raw = chan3_raw; + msg.chan4_raw = chan4_raw; + msg.chan5_raw = chan5_raw; + msg.chan6_raw = chan6_raw; + msg.chan7_raw = chan7_raw; + msg.chan8_raw = chan8_raw; + msg.chan9_raw = chan9_raw; + msg.chan10_raw = chan10_raw; + msg.chan11_raw = chan11_raw; + msg.chan12_raw = chan12_raw; + msg.chan13_raw = chan13_raw; + msg.chan14_raw = chan14_raw; + msg.chan15_raw = chan15_raw; + msg.chan16_raw = chan16_raw; + msg.chan17_raw = chan17_raw; + msg.chan18_raw = chan18_raw; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] //[FieldOffset(0)] - public uint time_boot_ms; + public ushort chan1_raw; - /// Absolute pressure [hPa] - [Units("[hPa]")] - [Description("Absolute pressure")] + /// RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] + //[FieldOffset(2)] + public ushort chan2_raw; + + /// RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] //[FieldOffset(4)] - public float press_abs; + public ushort chan3_raw; - /// Differential pressure 1 [hPa] - [Units("[hPa]")] - [Description("Differential pressure 1")] + /// RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] + //[FieldOffset(6)] + public ushort chan4_raw; + + /// RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] //[FieldOffset(8)] - public float press_diff; + public ushort chan5_raw; - /// Absolute pressure temperature [cdegC] - [Units("[cdegC]")] - [Description("Absolute pressure temperature")] + /// RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] + //[FieldOffset(10)] + public ushort chan6_raw; + + /// RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] //[FieldOffset(12)] - public short temperature; + public ushort chan7_raw; - /// Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. [cdegC] - [Units("[cdegC]")] - [Description("Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.")] + /// RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] //[FieldOffset(14)] - public short temperature_press_diff; + public ushort chan8_raw; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(16)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(17)] + public byte target_component; + + /// RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(18)] + public ushort chan9_raw; + + /// RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(20)] + public ushort chan10_raw; + + /// RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(22)] + public ushort chan11_raw; + + /// RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(24)] + public ushort chan12_raw; + + /// RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(26)] + public ushort chan13_raw; + + /// RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(28)] + public ushort chan14_raw; + + /// RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(30)] + public ushort chan15_raw; + + /// RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(32)] + public ushort chan16_raw; + + /// RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(34)] + public ushort chan17_raw; + + /// RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] + [Units("[us]")] + [Description("RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] + //[FieldOffset(36)] + public ushort chan18_raw; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). - public struct mavlink_attitude_t + /// extensions_start 14 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] + /// Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html. + public struct mavlink_mission_item_int_t { /// packet ordered constructor - public mavlink_attitude_t(uint time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) + public mavlink_mission_item_int_t(float param1,float param2,float param3,float param4,int x,int y,float z,ushort seq,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue,/*MAV_MISSION_TYPE*/byte mission_type) { - this.time_boot_ms = time_boot_ms; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.rollspeed = rollspeed; - this.pitchspeed = pitchspeed; - this.yawspeed = yawspeed; + this.param1 = param1; + this.param2 = param2; + this.param3 = param3; + this.param4 = param4; + this.x = x; + this.y = y; + this.z = z; + this.seq = seq; + this.command = command; + this.target_system = target_system; + this.target_component = target_component; + this.frame = frame; + this.current = current; + this.autocontinue = autocontinue; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_attitude_t PopulateXMLOrder(uint time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) + public static mavlink_mission_item_int_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,int x,int y,float z,/*MAV_MISSION_TYPE*/byte mission_type) { - var msg = new mavlink_attitude_t(); + var msg = new mavlink_mission_item_int_t(); - msg.time_boot_ms = time_boot_ms; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.rollspeed = rollspeed; - msg.pitchspeed = pitchspeed; - msg.yawspeed = yawspeed; + msg.target_system = target_system; + msg.target_component = target_component; + msg.seq = seq; + msg.frame = frame; + msg.command = command; + msg.current = current; + msg.autocontinue = autocontinue; + msg.param1 = param1; + msg.param2 = param2; + msg.param3 = param3; + msg.param4 = param4; + msg.x = x; + msg.y = y; + msg.z = z; + msg.mission_type = mission_type; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// PARAM1, see MAV_CMD enum + [Units("")] + [Description("PARAM1, see MAV_CMD enum")] //[FieldOffset(0)] - public uint time_boot_ms; + public float param1; - /// Roll angle (-pi..+pi) [rad] - [Units("[rad]")] - [Description("Roll angle (-pi..+pi)")] + /// PARAM2, see MAV_CMD enum + [Units("")] + [Description("PARAM2, see MAV_CMD enum")] //[FieldOffset(4)] - public float roll; + public float param2; - /// Pitch angle (-pi..+pi) [rad] - [Units("[rad]")] - [Description("Pitch angle (-pi..+pi)")] + /// PARAM3, see MAV_CMD enum + [Units("")] + [Description("PARAM3, see MAV_CMD enum")] //[FieldOffset(8)] - public float pitch; + public float param3; - /// Yaw angle (-pi..+pi) [rad] - [Units("[rad]")] - [Description("Yaw angle (-pi..+pi)")] + /// PARAM4, see MAV_CMD enum + [Units("")] + [Description("PARAM4, see MAV_CMD enum")] //[FieldOffset(12)] - public float yaw; + public float param4; - /// Roll angular speed [rad/s] - [Units("[rad/s]")] - [Description("Roll angular speed")] + /// PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + [Units("")] + [Description("PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7")] //[FieldOffset(16)] - public float rollspeed; + public int x; - /// Pitch angular speed [rad/s] - [Units("[rad/s]")] - [Description("Pitch angular speed")] + /// PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + [Units("")] + [Description("PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7")] //[FieldOffset(20)] - public float pitchspeed; + public int y; - /// Yaw angular speed [rad/s] - [Units("[rad/s]")] - [Description("Yaw angular speed")] + /// PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + [Units("")] + [Description("PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.")] //[FieldOffset(24)] - public float yawspeed; + public float z; + + /// Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + [Units("")] + [Description("Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).")] + //[FieldOffset(28)] + public ushort seq; + + /// The scheduled action for the waypoint. MAV_CMD + [Units("")] + [Description("The scheduled action for the waypoint.")] + //[FieldOffset(30)] + public /*MAV_CMD*/ushort command; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(32)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(33)] + public byte target_component; + + /// The coordinate system of the waypoint. MAV_FRAME + [Units("")] + [Description("The coordinate system of the waypoint.")] + //[FieldOffset(34)] + public /*MAV_FRAME*/byte frame; + + /// false:0, true:1 + [Units("")] + [Description("false:0, true:1")] + //[FieldOffset(35)] + public byte current; + + /// Autocontinue to next waypoint + [Units("")] + [Description("Autocontinue to next waypoint")] + //[FieldOffset(36)] + public byte autocontinue; + + /// Mission type. MAV_MISSION_TYPE + [Units("")] + [Description("Mission type.")] + //[FieldOffset(37)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; - /// extensions_start 8 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=48)] - /// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - public struct mavlink_attitude_quaternion_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Metrics typically displayed on a HUD for fixed wing aircraft. + public struct mavlink_vfr_hud_t { /// packet ordered constructor - public mavlink_attitude_quaternion_t(uint time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,float[] repr_offset_q) + public mavlink_vfr_hud_t(float airspeed,float groundspeed,float alt,float climb,short heading,ushort throttle) { - this.time_boot_ms = time_boot_ms; - this.q1 = q1; - this.q2 = q2; - this.q3 = q3; - this.q4 = q4; - this.rollspeed = rollspeed; - this.pitchspeed = pitchspeed; - this.yawspeed = yawspeed; - this.repr_offset_q = repr_offset_q; + this.airspeed = airspeed; + this.groundspeed = groundspeed; + this.alt = alt; + this.climb = climb; + this.heading = heading; + this.throttle = throttle; } /// packet xml order - public static mavlink_attitude_quaternion_t PopulateXMLOrder(uint time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,float[] repr_offset_q) + public static mavlink_vfr_hud_t PopulateXMLOrder(float airspeed,float groundspeed,short heading,ushort throttle,float alt,float climb) { - var msg = new mavlink_attitude_quaternion_t(); + var msg = new mavlink_vfr_hud_t(); - msg.time_boot_ms = time_boot_ms; - msg.q1 = q1; - msg.q2 = q2; - msg.q3 = q3; - msg.q4 = q4; - msg.rollspeed = rollspeed; - msg.pitchspeed = pitchspeed; - msg.yawspeed = yawspeed; - msg.repr_offset_q = repr_offset_q; + msg.airspeed = airspeed; + msg.groundspeed = groundspeed; + msg.heading = heading; + msg.throttle = throttle; + msg.alt = alt; + msg.climb = climb; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. [m/s] + [Units("[m/s]")] + [Description("Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.")] //[FieldOffset(0)] - public uint time_boot_ms; + public float airspeed; - /// Quaternion component 1, w (1 in null-rotation) - [Units("")] - [Description("Quaternion component 1, w (1 in null-rotation)")] + /// Current ground speed. [m/s] + [Units("[m/s]")] + [Description("Current ground speed.")] //[FieldOffset(4)] - public float q1; + public float groundspeed; - /// Quaternion component 2, x (0 in null-rotation) - [Units("")] - [Description("Quaternion component 2, x (0 in null-rotation)")] + /// Current altitude (MSL). [m] + [Units("[m]")] + [Description("Current altitude (MSL).")] //[FieldOffset(8)] - public float q2; + public float alt; - /// Quaternion component 3, y (0 in null-rotation) - [Units("")] - [Description("Quaternion component 3, y (0 in null-rotation)")] + /// Current climb rate. [m/s] + [Units("[m/s]")] + [Description("Current climb rate.")] //[FieldOffset(12)] - public float q3; - - /// Quaternion component 4, z (0 in null-rotation) - [Units("")] - [Description("Quaternion component 4, z (0 in null-rotation)")] - //[FieldOffset(16)] - public float q4; - - /// Roll angular speed [rad/s] - [Units("[rad/s]")] - [Description("Roll angular speed")] - //[FieldOffset(20)] - public float rollspeed; - - /// Pitch angular speed [rad/s] - [Units("[rad/s]")] - [Description("Pitch angular speed")] - //[FieldOffset(24)] - public float pitchspeed; - - /// Yaw angular speed [rad/s] - [Units("[rad/s]")] - [Description("Yaw angular speed")] - //[FieldOffset(28)] - public float yawspeed; + public float climb; - /// Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. - [Units("")] - [Description("Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] repr_offset_q; + /// Current heading in compass units (0-360, 0=north). [deg] + [Units("[deg]")] + [Description("Current heading in compass units (0-360, 0=north).")] + //[FieldOffset(16)] + public short heading; + + /// Current throttle setting (0 to 100). [%] + [Units("[%]")] + [Description("Current throttle setting (0 to 100).")] + //[FieldOffset(18)] + public ushort throttle; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - public struct mavlink_local_position_ned_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] + /// Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. The command microservice is documented at https://mavlink.io/en/services/command.html + public struct mavlink_command_int_t { /// packet ordered constructor - public mavlink_local_position_ned_t(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz) + public mavlink_command_int_t(float param1,float param2,float param3,float param4,int x,int y,float z,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue) { - this.time_boot_ms = time_boot_ms; + this.param1 = param1; + this.param2 = param2; + this.param3 = param3; + this.param4 = param4; this.x = x; this.y = y; this.z = z; - this.vx = vx; - this.vy = vy; - this.vz = vz; + this.command = command; + this.target_system = target_system; + this.target_component = target_component; + this.frame = frame; + this.current = current; + this.autocontinue = autocontinue; } /// packet xml order - public static mavlink_local_position_ned_t PopulateXMLOrder(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz) + public static mavlink_command_int_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,int x,int y,float z) { - var msg = new mavlink_local_position_ned_t(); + var msg = new mavlink_command_int_t(); - msg.time_boot_ms = time_boot_ms; + msg.target_system = target_system; + msg.target_component = target_component; + msg.frame = frame; + msg.command = command; + msg.current = current; + msg.autocontinue = autocontinue; + msg.param1 = param1; + msg.param2 = param2; + msg.param3 = param3; + msg.param4 = param4; msg.x = x; msg.y = y; msg.z = z; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// PARAM1, see MAV_CMD enum + [Units("")] + [Description("PARAM1, see MAV_CMD enum")] //[FieldOffset(0)] - public uint time_boot_ms; + public float param1; - /// X Position [m] - [Units("[m]")] - [Description("X Position")] + /// PARAM2, see MAV_CMD enum + [Units("")] + [Description("PARAM2, see MAV_CMD enum")] //[FieldOffset(4)] - public float x; + public float param2; - /// Y Position [m] - [Units("[m]")] - [Description("Y Position")] + /// PARAM3, see MAV_CMD enum + [Units("")] + [Description("PARAM3, see MAV_CMD enum")] //[FieldOffset(8)] - public float y; + public float param3; - /// Z Position [m] - [Units("[m]")] - [Description("Z Position")] + /// PARAM4, see MAV_CMD enum + [Units("")] + [Description("PARAM4, see MAV_CMD enum")] //[FieldOffset(12)] - public float z; + public float param4; - /// X Speed [m/s] - [Units("[m/s]")] - [Description("X Speed")] + /// PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + [Units("")] + [Description("PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7")] //[FieldOffset(16)] - public float vx; + public int x; - /// Y Speed [m/s] - [Units("[m/s]")] - [Description("Y Speed")] + /// PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + [Units("")] + [Description("PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7")] //[FieldOffset(20)] - public float vy; + public int y; - /// Z Speed [m/s] - [Units("[m/s]")] - [Description("Z Speed")] + /// PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). + [Units("")] + [Description("PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).")] //[FieldOffset(24)] - public float vz; + public float z; + + /// The scheduled action for the mission item. MAV_CMD + [Units("")] + [Description("The scheduled action for the mission item.")] + //[FieldOffset(28)] + public /*MAV_CMD*/ushort command; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(30)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(31)] + public byte target_component; + + /// The coordinate system of the COMMAND. MAV_FRAME + [Units("")] + [Description("The coordinate system of the COMMAND.")] + //[FieldOffset(32)] + public /*MAV_FRAME*/byte frame; + + /// Not used. + [Units("")] + [Description("Not used.")] + //[FieldOffset(33)] + public byte current; + + /// Not used (set 0). + [Units("")] + [Description("Not used (set 0).")] + //[FieldOffset(34)] + public byte autocontinue; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. - public struct mavlink_global_position_int_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// Send a command with up to seven parameters to the MAV. The command microservice is documented at https://mavlink.io/en/services/command.html + public struct mavlink_command_long_t { /// packet ordered constructor - public mavlink_global_position_int_t(uint time_boot_ms,int lat,int lon,int alt,int relative_alt,short vx,short vy,short vz,ushort hdg) + public mavlink_command_long_t(float param1,float param2,float param3,float param4,float param5,float param6,float param7,/*MAV_CMD*/ushort command,byte target_system,byte target_component,byte confirmation) { - this.time_boot_ms = time_boot_ms; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.relative_alt = relative_alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.hdg = hdg; + this.param1 = param1; + this.param2 = param2; + this.param3 = param3; + this.param4 = param4; + this.param5 = param5; + this.param6 = param6; + this.param7 = param7; + this.command = command; + this.target_system = target_system; + this.target_component = target_component; + this.confirmation = confirmation; } /// packet xml order - public static mavlink_global_position_int_t PopulateXMLOrder(uint time_boot_ms,int lat,int lon,int alt,int relative_alt,short vx,short vy,short vz,ushort hdg) + public static mavlink_command_long_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_CMD*/ushort command,byte confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) { - var msg = new mavlink_global_position_int_t(); + var msg = new mavlink_command_long_t(); - msg.time_boot_ms = time_boot_ms; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.relative_alt = relative_alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.hdg = hdg; + msg.target_system = target_system; + msg.target_component = target_component; + msg.command = command; + msg.confirmation = confirmation; + msg.param1 = param1; + msg.param2 = param2; + msg.param3 = param3; + msg.param4 = param4; + msg.param5 = param5; + msg.param6 = param6; + msg.param7 = param7; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Parameter 1 (for the specific command). + [Units("")] + [Description("Parameter 1 (for the specific command).")] //[FieldOffset(0)] - public uint time_boot_ms; + public float param1; - /// Latitude, expressed [degE7] - [Units("[degE7]")] - [Description("Latitude, expressed")] + /// Parameter 2 (for the specific command). + [Units("")] + [Description("Parameter 2 (for the specific command).")] //[FieldOffset(4)] - public int lat; + public float param2; - /// Longitude, expressed [degE7] - [Units("[degE7]")] - [Description("Longitude, expressed")] + /// Parameter 3 (for the specific command). + [Units("")] + [Description("Parameter 3 (for the specific command).")] //[FieldOffset(8)] - public int lon; + public float param3; - /// Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.")] + /// Parameter 4 (for the specific command). + [Units("")] + [Description("Parameter 4 (for the specific command).")] //[FieldOffset(12)] - public int alt; + public float param4; - /// Altitude above home [mm] - [Units("[mm]")] - [Description("Altitude above home")] + /// Parameter 5 (for the specific command). + [Units("")] + [Description("Parameter 5 (for the specific command).")] //[FieldOffset(16)] - public int relative_alt; + public float param5; - /// Ground X Speed (Latitude, positive north) [cm/s] - [Units("[cm/s]")] - [Description("Ground X Speed (Latitude, positive north)")] + /// Parameter 6 (for the specific command). + [Units("")] + [Description("Parameter 6 (for the specific command).")] //[FieldOffset(20)] - public short vx; - - /// Ground Y Speed (Longitude, positive east) [cm/s] - [Units("[cm/s]")] - [Description("Ground Y Speed (Longitude, positive east)")] - //[FieldOffset(22)] - public short vy; + public float param6; - /// Ground Z Speed (Altitude, positive down) [cm/s] - [Units("[cm/s]")] - [Description("Ground Z Speed (Altitude, positive down)")] + /// Parameter 7 (for the specific command). + [Units("")] + [Description("Parameter 7 (for the specific command).")] //[FieldOffset(24)] - public short vz; + public float param7; - /// Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX [cdeg] - [Units("[cdeg]")] - [Description("Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX")] - //[FieldOffset(26)] - public ushort hdg; + /// Command ID (of command to send). MAV_CMD + [Units("")] + [Description("Command ID (of command to send).")] + //[FieldOffset(28)] + public /*MAV_CMD*/ushort command; + + /// System which should execute the command + [Units("")] + [Description("System which should execute the command")] + //[FieldOffset(30)] + public byte target_system; + + /// Component which should execute the command, 0 for all components + [Units("")] + [Description("Component which should execute the command, 0 for all components")] + //[FieldOffset(31)] + public byte target_component; + + /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + [Units("")] + [Description("0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)")] + //[FieldOffset(32)] + public byte confirmation; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - /// The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. - public struct mavlink_rc_channels_scaled_t + /// extensions_start 2 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=10)] + /// Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html + public struct mavlink_command_ack_t { /// packet ordered constructor - public mavlink_rc_channels_scaled_t(uint time_boot_ms,short chan1_scaled,short chan2_scaled,short chan3_scaled,short chan4_scaled,short chan5_scaled,short chan6_scaled,short chan7_scaled,short chan8_scaled,byte port,byte rssi) + public mavlink_command_ack_t(/*MAV_CMD*/ushort command,/*MAV_RESULT*/byte result,byte progress,int result_param2,byte target_system,byte target_component) { - this.time_boot_ms = time_boot_ms; - this.chan1_scaled = chan1_scaled; - this.chan2_scaled = chan2_scaled; - this.chan3_scaled = chan3_scaled; - this.chan4_scaled = chan4_scaled; - this.chan5_scaled = chan5_scaled; - this.chan6_scaled = chan6_scaled; - this.chan7_scaled = chan7_scaled; - this.chan8_scaled = chan8_scaled; - this.port = port; - this.rssi = rssi; + this.command = command; + this.result = result; + this.progress = progress; + this.result_param2 = result_param2; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_rc_channels_scaled_t PopulateXMLOrder(uint time_boot_ms,byte port,short chan1_scaled,short chan2_scaled,short chan3_scaled,short chan4_scaled,short chan5_scaled,short chan6_scaled,short chan7_scaled,short chan8_scaled,byte rssi) + public static mavlink_command_ack_t PopulateXMLOrder(/*MAV_CMD*/ushort command,/*MAV_RESULT*/byte result,byte progress,int result_param2,byte target_system,byte target_component) { - var msg = new mavlink_rc_channels_scaled_t(); + var msg = new mavlink_command_ack_t(); - msg.time_boot_ms = time_boot_ms; - msg.port = port; - msg.chan1_scaled = chan1_scaled; - msg.chan2_scaled = chan2_scaled; - msg.chan3_scaled = chan3_scaled; - msg.chan4_scaled = chan4_scaled; - msg.chan5_scaled = chan5_scaled; - msg.chan6_scaled = chan6_scaled; - msg.chan7_scaled = chan7_scaled; - msg.chan8_scaled = chan8_scaled; - msg.rssi = rssi; + msg.command = command; + msg.result = result; + msg.progress = progress; + msg.result_param2 = result_param2; + msg.target_system = target_system; + msg.target_component = target_component; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// RC channel 1 value scaled. - [Units("")] - [Description("RC channel 1 value scaled.")] - //[FieldOffset(4)] - public short chan1_scaled; - - /// RC channel 2 value scaled. - [Units("")] - [Description("RC channel 2 value scaled.")] - //[FieldOffset(6)] - public short chan2_scaled; - - /// RC channel 3 value scaled. - [Units("")] - [Description("RC channel 3 value scaled.")] - //[FieldOffset(8)] - public short chan3_scaled; - - /// RC channel 4 value scaled. - [Units("")] - [Description("RC channel 4 value scaled.")] - //[FieldOffset(10)] - public short chan4_scaled; - - /// RC channel 5 value scaled. + /// Command ID (of acknowledged command). MAV_CMD [Units("")] - [Description("RC channel 5 value scaled.")] - //[FieldOffset(12)] - public short chan5_scaled; + [Description("Command ID (of acknowledged command).")] + //[FieldOffset(0)] + public /*MAV_CMD*/ushort command; - /// RC channel 6 value scaled. + /// Result of command. MAV_RESULT [Units("")] - [Description("RC channel 6 value scaled.")] - //[FieldOffset(14)] - public short chan6_scaled; + [Description("Result of command.")] + //[FieldOffset(2)] + public /*MAV_RESULT*/byte result; - /// RC channel 7 value scaled. + /// Also used as result_param1, it can be set with a enum containing the errors reasons of why the command was denied or the progress percentage or 255 if unknown the progress when result is MAV_RESULT_IN_PROGRESS. [Units("")] - [Description("RC channel 7 value scaled.")] - //[FieldOffset(16)] - public short chan7_scaled; + [Description("Also used as result_param1, it can be set with a enum containing the errors reasons of why the command was denied or the progress percentage or 255 if unknown the progress when result is MAV_RESULT_IN_PROGRESS.")] + //[FieldOffset(3)] + public byte progress; - /// RC channel 8 value scaled. + /// Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied. [Units("")] - [Description("RC channel 8 value scaled.")] - //[FieldOffset(18)] - public short chan8_scaled; + [Description("Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.")] + //[FieldOffset(4)] + public int result_param2; - /// Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + /// System which requested the command to be executed [Units("")] - [Description("Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.")] - //[FieldOffset(20)] - public byte port; + [Description("System which requested the command to be executed")] + //[FieldOffset(8)] + public byte target_system; - /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + /// Component which requested the command to be executed [Units("")] - [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(21)] - public byte rssi; + [Description("Component which requested the command to be executed")] + //[FieldOffset(9)] + public byte target_component; }; /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - /// The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification. - public struct mavlink_rc_channels_raw_t + /// Setpoint in roll, pitch, yaw and thrust from the operator + public struct mavlink_manual_setpoint_t { /// packet ordered constructor - public mavlink_rc_channels_raw_t(uint time_boot_ms,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,byte port,byte rssi) + public mavlink_manual_setpoint_t(uint time_boot_ms,float roll,float pitch,float yaw,float thrust,byte mode_switch,byte manual_override_switch) { this.time_boot_ms = time_boot_ms; - this.chan1_raw = chan1_raw; - this.chan2_raw = chan2_raw; - this.chan3_raw = chan3_raw; - this.chan4_raw = chan4_raw; - this.chan5_raw = chan5_raw; - this.chan6_raw = chan6_raw; - this.chan7_raw = chan7_raw; - this.chan8_raw = chan8_raw; - this.port = port; - this.rssi = rssi; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.thrust = thrust; + this.mode_switch = mode_switch; + this.manual_override_switch = manual_override_switch; } /// packet xml order - public static mavlink_rc_channels_raw_t PopulateXMLOrder(uint time_boot_ms,byte port,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,byte rssi) + public static mavlink_manual_setpoint_t PopulateXMLOrder(uint time_boot_ms,float roll,float pitch,float yaw,float thrust,byte mode_switch,byte manual_override_switch) { - var msg = new mavlink_rc_channels_raw_t(); + var msg = new mavlink_manual_setpoint_t(); msg.time_boot_ms = time_boot_ms; - msg.port = port; - msg.chan1_raw = chan1_raw; - msg.chan2_raw = chan2_raw; - msg.chan3_raw = chan3_raw; - msg.chan4_raw = chan4_raw; - msg.chan5_raw = chan5_raw; - msg.chan6_raw = chan6_raw; - msg.chan7_raw = chan7_raw; - msg.chan8_raw = chan8_raw; - msg.rssi = rssi; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.thrust = thrust; + msg.mode_switch = mode_switch; + msg.manual_override_switch = manual_override_switch; return msg; } @@ -14173,1367 +19852,1827 @@ public static mavlink_rc_channels_raw_t PopulateXMLOrder(uint time_boot_ms,byte //[FieldOffset(0)] public uint time_boot_ms; - /// RC channel 1 value. [us] - [Units("[us]")] - [Description("RC channel 1 value.")] + /// Desired roll rate [rad/s] + [Units("[rad/s]")] + [Description("Desired roll rate")] //[FieldOffset(4)] - public ushort chan1_raw; - - /// RC channel 2 value. [us] - [Units("[us]")] - [Description("RC channel 2 value.")] - //[FieldOffset(6)] - public ushort chan2_raw; + public float roll; - /// RC channel 3 value. [us] - [Units("[us]")] - [Description("RC channel 3 value.")] + /// Desired pitch rate [rad/s] + [Units("[rad/s]")] + [Description("Desired pitch rate")] //[FieldOffset(8)] - public ushort chan3_raw; - - /// RC channel 4 value. [us] - [Units("[us]")] - [Description("RC channel 4 value.")] - //[FieldOffset(10)] - public ushort chan4_raw; + public float pitch; - /// RC channel 5 value. [us] - [Units("[us]")] - [Description("RC channel 5 value.")] + /// Desired yaw rate [rad/s] + [Units("[rad/s]")] + [Description("Desired yaw rate")] //[FieldOffset(12)] - public ushort chan5_raw; - - /// RC channel 6 value. [us] - [Units("[us]")] - [Description("RC channel 6 value.")] - //[FieldOffset(14)] - public ushort chan6_raw; + public float yaw; - /// RC channel 7 value. [us] - [Units("[us]")] - [Description("RC channel 7 value.")] + /// Collective thrust, normalized to 0 .. 1 + [Units("")] + [Description("Collective thrust, normalized to 0 .. 1")] //[FieldOffset(16)] - public ushort chan7_raw; - - /// RC channel 8 value. [us] - [Units("[us]")] - [Description("RC channel 8 value.")] - //[FieldOffset(18)] - public ushort chan8_raw; + public float thrust; - /// Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + /// Flight mode switch position, 0.. 255 [Units("")] - [Description("Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.")] + [Description("Flight mode switch position, 0.. 255")] //[FieldOffset(20)] - public byte port; + public byte mode_switch; - /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + /// Override mode switch position, 0.. 255 [Units("")] - [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] + [Description("Override mode switch position, 0.. 255")] //[FieldOffset(21)] - public byte rssi; + public byte manual_override_switch; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - /// Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. - public struct mavlink_servo_output_raw_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=39)] + /// Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). + public struct mavlink_set_attitude_target_t { /// packet ordered constructor - public mavlink_servo_output_raw_t(uint time_usec,ushort servo1_raw,ushort servo2_raw,ushort servo3_raw,ushort servo4_raw,ushort servo5_raw,ushort servo6_raw,ushort servo7_raw,ushort servo8_raw,byte port,ushort servo9_raw,ushort servo10_raw,ushort servo11_raw,ushort servo12_raw,ushort servo13_raw,ushort servo14_raw,ushort servo15_raw,ushort servo16_raw) + public mavlink_set_attitude_target_t(uint time_boot_ms,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust,byte target_system,byte target_component,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask) { - this.time_usec = time_usec; - this.servo1_raw = servo1_raw; - this.servo2_raw = servo2_raw; - this.servo3_raw = servo3_raw; - this.servo4_raw = servo4_raw; - this.servo5_raw = servo5_raw; - this.servo6_raw = servo6_raw; - this.servo7_raw = servo7_raw; - this.servo8_raw = servo8_raw; - this.port = port; - this.servo9_raw = servo9_raw; - this.servo10_raw = servo10_raw; - this.servo11_raw = servo11_raw; - this.servo12_raw = servo12_raw; - this.servo13_raw = servo13_raw; - this.servo14_raw = servo14_raw; - this.servo15_raw = servo15_raw; - this.servo16_raw = servo16_raw; + this.time_boot_ms = time_boot_ms; + this.q = q; + this.body_roll_rate = body_roll_rate; + this.body_pitch_rate = body_pitch_rate; + this.body_yaw_rate = body_yaw_rate; + this.thrust = thrust; + this.target_system = target_system; + this.target_component = target_component; + this.type_mask = type_mask; } /// packet xml order - public static mavlink_servo_output_raw_t PopulateXMLOrder(uint time_usec,byte port,ushort servo1_raw,ushort servo2_raw,ushort servo3_raw,ushort servo4_raw,ushort servo5_raw,ushort servo6_raw,ushort servo7_raw,ushort servo8_raw,ushort servo9_raw,ushort servo10_raw,ushort servo11_raw,ushort servo12_raw,ushort servo13_raw,ushort servo14_raw,ushort servo15_raw,ushort servo16_raw) + public static mavlink_set_attitude_target_t PopulateXMLOrder(uint time_boot_ms,byte target_system,byte target_component,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) { - var msg = new mavlink_servo_output_raw_t(); + var msg = new mavlink_set_attitude_target_t(); - msg.time_usec = time_usec; - msg.port = port; - msg.servo1_raw = servo1_raw; - msg.servo2_raw = servo2_raw; - msg.servo3_raw = servo3_raw; - msg.servo4_raw = servo4_raw; - msg.servo5_raw = servo5_raw; - msg.servo6_raw = servo6_raw; - msg.servo7_raw = servo7_raw; - msg.servo8_raw = servo8_raw; - msg.servo9_raw = servo9_raw; - msg.servo10_raw = servo10_raw; - msg.servo11_raw = servo11_raw; - msg.servo12_raw = servo12_raw; - msg.servo13_raw = servo13_raw; - msg.servo14_raw = servo14_raw; - msg.servo15_raw = servo15_raw; - msg.servo16_raw = servo16_raw; + msg.time_boot_ms = time_boot_ms; + msg.target_system = target_system; + msg.target_component = target_component; + msg.type_mask = type_mask; + msg.q = q; + msg.body_roll_rate = body_roll_rate; + msg.body_pitch_rate = body_pitch_rate; + msg.body_yaw_rate = body_yaw_rate; + msg.thrust = thrust; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public uint time_usec; + public uint time_boot_ms; - /// Servo output 1 value [us] - [Units("[us]")] - [Description("Servo output 1 value")] + /// Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + [Units("")] + [Description("Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] //[FieldOffset(4)] - public ushort servo1_raw; - - /// Servo output 2 value [us] - [Units("[us]")] - [Description("Servo output 2 value")] - //[FieldOffset(6)] - public ushort servo2_raw; - - /// Servo output 3 value [us] - [Units("[us]")] - [Description("Servo output 3 value")] - //[FieldOffset(8)] - public ushort servo3_raw; - - /// Servo output 4 value [us] - [Units("[us]")] - [Description("Servo output 4 value")] - //[FieldOffset(10)] - public ushort servo4_raw; - - /// Servo output 5 value [us] - [Units("[us]")] - [Description("Servo output 5 value")] - //[FieldOffset(12)] - public ushort servo5_raw; - - /// Servo output 6 value [us] - [Units("[us]")] - [Description("Servo output 6 value")] - //[FieldOffset(14)] - public ushort servo6_raw; - - /// Servo output 7 value [us] - [Units("[us]")] - [Description("Servo output 7 value")] - //[FieldOffset(16)] - public ushort servo7_raw; - - /// Servo output 8 value [us] - [Units("[us]")] - [Description("Servo output 8 value")] - //[FieldOffset(18)] - public ushort servo8_raw; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - [Units("")] - [Description("Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.")] + /// Body roll rate [rad/s] + [Units("[rad/s]")] + [Description("Body roll rate")] //[FieldOffset(20)] - public byte port; - - /// Servo output 9 value [us] - [Units("[us]")] - [Description("Servo output 9 value")] - //[FieldOffset(21)] - public ushort servo9_raw; - - /// Servo output 10 value [us] - [Units("[us]")] - [Description("Servo output 10 value")] - //[FieldOffset(23)] - public ushort servo10_raw; + public float body_roll_rate; - /// Servo output 11 value [us] - [Units("[us]")] - [Description("Servo output 11 value")] - //[FieldOffset(25)] - public ushort servo11_raw; + /// Body pitch rate [rad/s] + [Units("[rad/s]")] + [Description("Body pitch rate")] + //[FieldOffset(24)] + public float body_pitch_rate; - /// Servo output 12 value [us] - [Units("[us]")] - [Description("Servo output 12 value")] - //[FieldOffset(27)] - public ushort servo12_raw; + /// Body yaw rate [rad/s] + [Units("[rad/s]")] + [Description("Body yaw rate")] + //[FieldOffset(28)] + public float body_yaw_rate; - /// Servo output 13 value [us] - [Units("[us]")] - [Description("Servo output 13 value")] - //[FieldOffset(29)] - public ushort servo13_raw; + /// Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + [Units("")] + [Description("Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)")] + //[FieldOffset(32)] + public float thrust; - /// Servo output 14 value [us] - [Units("[us]")] - [Description("Servo output 14 value")] - //[FieldOffset(31)] - public ushort servo14_raw; + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(36)] + public byte target_system; - /// Servo output 15 value [us] - [Units("[us]")] - [Description("Servo output 15 value")] - //[FieldOffset(33)] - public ushort servo15_raw; + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(37)] + public byte target_component; - /// Servo output 16 value [us] - [Units("[us]")] - [Description("Servo output 16 value")] - //[FieldOffset(35)] - public ushort servo16_raw; + /// Bitmap to indicate which dimensions should be ignored by the vehicle. ATTITUDE_TARGET_TYPEMASK bitmask + [Units("")] + [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] + //[FieldOffset(38)] + public /*ATTITUDE_TARGET_TYPEMASK*/byte type_mask; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] - /// Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint. - public struct mavlink_mission_request_partial_list_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] + /// Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. + public struct mavlink_attitude_target_t { /// packet ordered constructor - public mavlink_mission_request_partial_list_t(short start_index,short end_index,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_attitude_target_t(uint time_boot_ms,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask) { - this.start_index = start_index; - this.end_index = end_index; - this.target_system = target_system; - this.target_component = target_component; - this.mission_type = mission_type; + this.time_boot_ms = time_boot_ms; + this.q = q; + this.body_roll_rate = body_roll_rate; + this.body_pitch_rate = body_pitch_rate; + this.body_yaw_rate = body_yaw_rate; + this.thrust = thrust; + this.type_mask = type_mask; } /// packet xml order - public static mavlink_mission_request_partial_list_t PopulateXMLOrder(byte target_system,byte target_component,short start_index,short end_index,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_attitude_target_t PopulateXMLOrder(uint time_boot_ms,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) { - var msg = new mavlink_mission_request_partial_list_t(); + var msg = new mavlink_attitude_target_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.start_index = start_index; - msg.end_index = end_index; - msg.mission_type = mission_type; + msg.time_boot_ms = time_boot_ms; + msg.type_mask = type_mask; + msg.q = q; + msg.body_roll_rate = body_roll_rate; + msg.body_pitch_rate = body_pitch_rate; + msg.body_yaw_rate = body_yaw_rate; + msg.thrust = thrust; return msg; } - /// Start index - [Units("")] - [Description("Start index")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public short start_index; - - /// End index, -1 by default (-1: send list to end). Else a valid index of the list - [Units("")] - [Description("End index, -1 by default (-1: send list to end). Else a valid index of the list")] - //[FieldOffset(2)] - public short end_index; + public uint time_boot_ms; - /// System ID + /// Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) [Units("")] - [Description("System ID")] + [Description("Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] //[FieldOffset(4)] - public byte target_system; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Component ID + /// Body roll rate [rad/s] + [Units("[rad/s]")] + [Description("Body roll rate")] + //[FieldOffset(20)] + public float body_roll_rate; + + /// Body pitch rate [rad/s] + [Units("[rad/s]")] + [Description("Body pitch rate")] + //[FieldOffset(24)] + public float body_pitch_rate; + + /// Body yaw rate [rad/s] + [Units("[rad/s]")] + [Description("Body yaw rate")] + //[FieldOffset(28)] + public float body_yaw_rate; + + /// Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) [Units("")] - [Description("Component ID")] - //[FieldOffset(5)] - public byte target_component; + [Description("Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)")] + //[FieldOffset(32)] + public float thrust; - /// Mission type. MAV_MISSION_TYPE + /// Bitmap to indicate which dimensions should be ignored by the vehicle. ATTITUDE_TARGET_TYPEMASK bitmask [Units("")] - [Description("Mission type.")] - //[FieldOffset(6)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] + //[FieldOffset(36)] + public /*ATTITUDE_TARGET_TYPEMASK*/byte type_mask; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] - /// This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! - public struct mavlink_mission_write_partial_list_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] + /// Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). + public struct mavlink_set_position_target_local_ned_t { /// packet ordered constructor - public mavlink_mission_write_partial_list_t(short start_index,short end_index,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_set_position_target_local_ned_t(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame) { - this.start_index = start_index; - this.end_index = end_index; + this.time_boot_ms = time_boot_ms; + this.x = x; + this.y = y; + this.z = z; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.afx = afx; + this.afy = afy; + this.afz = afz; + this.yaw = yaw; + this.yaw_rate = yaw_rate; + this.type_mask = type_mask; this.target_system = target_system; this.target_component = target_component; - this.mission_type = mission_type; + this.coordinate_frame = coordinate_frame; } /// packet xml order - public static mavlink_mission_write_partial_list_t PopulateXMLOrder(byte target_system,byte target_component,short start_index,short end_index,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_set_position_target_local_ned_t PopulateXMLOrder(uint time_boot_ms,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) { - var msg = new mavlink_mission_write_partial_list_t(); + var msg = new mavlink_set_position_target_local_ned_t(); + msg.time_boot_ms = time_boot_ms; msg.target_system = target_system; msg.target_component = target_component; - msg.start_index = start_index; - msg.end_index = end_index; - msg.mission_type = mission_type; + msg.coordinate_frame = coordinate_frame; + msg.type_mask = type_mask; + msg.x = x; + msg.y = y; + msg.z = z; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.afx = afx; + msg.afy = afy; + msg.afz = afz; + msg.yaw = yaw; + msg.yaw_rate = yaw_rate; return msg; } - /// Start index. Must be smaller / equal to the largest index of the current onboard list. - [Units("")] - [Description("Start index. Must be smaller / equal to the largest index of the current onboard list.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public short start_index; + public uint time_boot_ms; - /// End index, equal or greater than start index. + /// X Position in NED frame [m] + [Units("[m]")] + [Description("X Position in NED frame")] + //[FieldOffset(4)] + public float x; + + /// Y Position in NED frame [m] + [Units("[m]")] + [Description("Y Position in NED frame")] + //[FieldOffset(8)] + public float y; + + /// Z Position in NED frame (note, altitude is negative in NED) [m] + [Units("[m]")] + [Description("Z Position in NED frame (note, altitude is negative in NED)")] + //[FieldOffset(12)] + public float z; + + /// X velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("X velocity in NED frame")] + //[FieldOffset(16)] + public float vx; + + /// Y velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Y velocity in NED frame")] + //[FieldOffset(20)] + public float vy; + + /// Z velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Z velocity in NED frame")] + //[FieldOffset(24)] + public float vz; + + /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(28)] + public float afx; + + /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(32)] + public float afy; + + /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(36)] + public float afz; + + /// yaw setpoint [rad] + [Units("[rad]")] + [Description("yaw setpoint")] + //[FieldOffset(40)] + public float yaw; + + /// yaw rate setpoint [rad/s] + [Units("[rad/s]")] + [Description("yaw rate setpoint")] + //[FieldOffset(44)] + public float yaw_rate; + + /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask [Units("")] - [Description("End index, equal or greater than start index.")] - //[FieldOffset(2)] - public short end_index; + [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] + //[FieldOffset(48)] + public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; /// System ID [Units("")] [Description("System ID")] - //[FieldOffset(4)] + //[FieldOffset(50)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(5)] + //[FieldOffset(51)] public byte target_component; - /// Mission type. MAV_MISSION_TYPE + /// Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 MAV_FRAME [Units("")] - [Description("Mission type.")] - //[FieldOffset(6)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9")] + //[FieldOffset(52)] + public /*MAV_FRAME*/byte coordinate_frame; }; - [Obsolete] - /// extensions_start 14 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] - /// Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html. - public struct mavlink_mission_item_t + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] + /// Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. + public struct mavlink_position_target_local_ned_t { /// packet ordered constructor - public mavlink_mission_item_t(float param1,float param2,float param3,float param4,float x,float y,float z,ushort seq,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_position_target_local_ned_t(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,/*MAV_FRAME*/byte coordinate_frame) { - this.param1 = param1; - this.param2 = param2; - this.param3 = param3; - this.param4 = param4; + this.time_boot_ms = time_boot_ms; this.x = x; this.y = y; this.z = z; - this.seq = seq; - this.command = command; - this.target_system = target_system; - this.target_component = target_component; - this.frame = frame; - this.current = current; - this.autocontinue = autocontinue; - this.mission_type = mission_type; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.afx = afx; + this.afy = afy; + this.afz = afz; + this.yaw = yaw; + this.yaw_rate = yaw_rate; + this.type_mask = type_mask; + this.coordinate_frame = coordinate_frame; } /// packet xml order - public static mavlink_mission_item_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_position_target_local_ned_t PopulateXMLOrder(uint time_boot_ms,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) { - var msg = new mavlink_mission_item_t(); + var msg = new mavlink_position_target_local_ned_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.seq = seq; - msg.frame = frame; - msg.command = command; - msg.current = current; - msg.autocontinue = autocontinue; - msg.param1 = param1; - msg.param2 = param2; - msg.param3 = param3; - msg.param4 = param4; + msg.time_boot_ms = time_boot_ms; + msg.coordinate_frame = coordinate_frame; + msg.type_mask = type_mask; msg.x = x; msg.y = y; msg.z = z; - msg.mission_type = mission_type; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.afx = afx; + msg.afy = afy; + msg.afz = afz; + msg.yaw = yaw; + msg.yaw_rate = yaw_rate; return msg; } - /// PARAM1, see MAV_CMD enum - [Units("")] - [Description("PARAM1, see MAV_CMD enum")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public float param1; + public uint time_boot_ms; - /// PARAM2, see MAV_CMD enum - [Units("")] - [Description("PARAM2, see MAV_CMD enum")] + /// X Position in NED frame [m] + [Units("[m]")] + [Description("X Position in NED frame")] //[FieldOffset(4)] - public float param2; + public float x; - /// PARAM3, see MAV_CMD enum - [Units("")] - [Description("PARAM3, see MAV_CMD enum")] + /// Y Position in NED frame [m] + [Units("[m]")] + [Description("Y Position in NED frame")] //[FieldOffset(8)] - public float param3; + public float y; - /// PARAM4, see MAV_CMD enum - [Units("")] - [Description("PARAM4, see MAV_CMD enum")] + /// Z Position in NED frame (note, altitude is negative in NED) [m] + [Units("[m]")] + [Description("Z Position in NED frame (note, altitude is negative in NED)")] //[FieldOffset(12)] - public float param4; + public float z; - /// PARAM5 / local: X coordinate, global: latitude - [Units("")] - [Description("PARAM5 / local: X coordinate, global: latitude")] + /// X velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("X velocity in NED frame")] //[FieldOffset(16)] - public float x; + public float vx; - /// PARAM6 / local: Y coordinate, global: longitude - [Units("")] - [Description("PARAM6 / local: Y coordinate, global: longitude")] + /// Y velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Y velocity in NED frame")] //[FieldOffset(20)] - public float y; + public float vy; - /// PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). - [Units("")] - [Description("PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).")] + /// Z velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Z velocity in NED frame")] //[FieldOffset(24)] - public float z; + public float vz; - /// Sequence - [Units("")] - [Description("Sequence")] + /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] //[FieldOffset(28)] - public ushort seq; - - /// The scheduled action for the waypoint. MAV_CMD - [Units("")] - [Description("The scheduled action for the waypoint.")] - //[FieldOffset(30)] - public /*MAV_CMD*/ushort command; + public float afx; - /// System ID - [Units("")] - [Description("System ID")] + /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] //[FieldOffset(32)] - public byte target_system; + public float afy; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(33)] - public byte target_component; + /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(36)] + public float afz; - /// The coordinate system of the waypoint. MAV_FRAME - [Units("")] - [Description("The coordinate system of the waypoint.")] - //[FieldOffset(34)] - public /*MAV_FRAME*/byte frame; + /// yaw setpoint [rad] + [Units("[rad]")] + [Description("yaw setpoint")] + //[FieldOffset(40)] + public float yaw; - /// false:0, true:1 - [Units("")] - [Description("false:0, true:1")] - //[FieldOffset(35)] - public byte current; + /// yaw rate setpoint [rad/s] + [Units("[rad/s]")] + [Description("yaw rate setpoint")] + //[FieldOffset(44)] + public float yaw_rate; - /// Autocontinue to next waypoint + /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask [Units("")] - [Description("Autocontinue to next waypoint")] - //[FieldOffset(36)] - public byte autocontinue; + [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] + //[FieldOffset(48)] + public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; - /// Mission type. MAV_MISSION_TYPE + /// Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 MAV_FRAME [Units("")] - [Description("Mission type.")] - //[FieldOffset(37)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9")] + //[FieldOffset(50)] + public /*MAV_FRAME*/byte coordinate_frame; }; - [Obsolete] - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html - public struct mavlink_mission_request_t + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] + /// Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). + public struct mavlink_set_position_target_global_int_t { /// packet ordered constructor - public mavlink_mission_request_t(ushort seq,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_set_position_target_global_int_t(uint time_boot_ms,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame) { - this.seq = seq; + this.time_boot_ms = time_boot_ms; + this.lat_int = lat_int; + this.lon_int = lon_int; + this.alt = alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.afx = afx; + this.afy = afy; + this.afz = afz; + this.yaw = yaw; + this.yaw_rate = yaw_rate; + this.type_mask = type_mask; this.target_system = target_system; this.target_component = target_component; - this.mission_type = mission_type; + this.coordinate_frame = coordinate_frame; } /// packet xml order - public static mavlink_mission_request_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_set_position_target_global_int_t PopulateXMLOrder(uint time_boot_ms,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) { - var msg = new mavlink_mission_request_t(); + var msg = new mavlink_set_position_target_global_int_t(); + msg.time_boot_ms = time_boot_ms; msg.target_system = target_system; msg.target_component = target_component; - msg.seq = seq; - msg.mission_type = mission_type; + msg.coordinate_frame = coordinate_frame; + msg.type_mask = type_mask; + msg.lat_int = lat_int; + msg.lon_int = lon_int; + msg.alt = alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.afx = afx; + msg.afy = afy; + msg.afz = afz; + msg.yaw = yaw; + msg.yaw_rate = yaw_rate; return msg; } - /// Sequence - [Units("")] - [Description("Sequence")] + /// Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.")] //[FieldOffset(0)] - public ushort seq; + public uint time_boot_ms; + + /// Latitude in WGS84 frame [degE7] + [Units("[degE7]")] + [Description("Latitude in WGS84 frame")] + //[FieldOffset(4)] + public int lat_int; + + /// Longitude in WGS84 frame [degE7] + [Units("[degE7]")] + [Description("Longitude in WGS84 frame")] + //[FieldOffset(8)] + public int lon_int; + + /// Altitude (MSL, Relative to home, or AGL - depending on frame) [m] + [Units("[m]")] + [Description("Altitude (MSL, Relative to home, or AGL - depending on frame)")] + //[FieldOffset(12)] + public float alt; + + /// X velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("X velocity in NED frame")] + //[FieldOffset(16)] + public float vx; + + /// Y velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Y velocity in NED frame")] + //[FieldOffset(20)] + public float vy; + + /// Z velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Z velocity in NED frame")] + //[FieldOffset(24)] + public float vz; + + /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(28)] + public float afx; + + /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(32)] + public float afy; + + /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(36)] + public float afz; + + /// yaw setpoint [rad] + [Units("[rad]")] + [Description("yaw setpoint")] + //[FieldOffset(40)] + public float yaw; + + /// yaw rate setpoint [rad/s] + [Units("[rad/s]")] + [Description("yaw rate setpoint")] + //[FieldOffset(44)] + public float yaw_rate; + + /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask + [Units("")] + [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] + //[FieldOffset(48)] + public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; /// System ID [Units("")] [Description("System ID")] - //[FieldOffset(2)] + //[FieldOffset(50)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(3)] + //[FieldOffset(51)] public byte target_component; - /// Mission type. MAV_MISSION_TYPE + /// Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated) MAV_FRAME [Units("")] - [Description("Mission type.")] - //[FieldOffset(4)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)")] + //[FieldOffset(52)] + public /*MAV_FRAME*/byte coordinate_frame; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - /// 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). - public struct mavlink_mission_set_current_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] + /// Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. + public struct mavlink_position_target_global_int_t { /// packet ordered constructor - public mavlink_mission_set_current_t(ushort seq,byte target_system,byte target_component) + public mavlink_position_target_global_int_t(uint time_boot_ms,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,/*MAV_FRAME*/byte coordinate_frame) { - this.seq = seq; - this.target_system = target_system; - this.target_component = target_component; + this.time_boot_ms = time_boot_ms; + this.lat_int = lat_int; + this.lon_int = lon_int; + this.alt = alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.afx = afx; + this.afy = afy; + this.afz = afz; + this.yaw = yaw; + this.yaw_rate = yaw_rate; + this.type_mask = type_mask; + this.coordinate_frame = coordinate_frame; } /// packet xml order - public static mavlink_mission_set_current_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq) + public static mavlink_position_target_global_int_t PopulateXMLOrder(uint time_boot_ms,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) { - var msg = new mavlink_mission_set_current_t(); + var msg = new mavlink_position_target_global_int_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.seq = seq; + msg.time_boot_ms = time_boot_ms; + msg.coordinate_frame = coordinate_frame; + msg.type_mask = type_mask; + msg.lat_int = lat_int; + msg.lon_int = lon_int; + msg.alt = alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.afx = afx; + msg.afy = afy; + msg.afz = afz; + msg.yaw = yaw; + msg.yaw_rate = yaw_rate; return msg; } - /// Sequence - [Units("")] - [Description("Sequence")] + /// Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.")] //[FieldOffset(0)] - public ushort seq; + public uint time_boot_ms; - /// System ID + /// Latitude in WGS84 frame [degE7] + [Units("[degE7]")] + [Description("Latitude in WGS84 frame")] + //[FieldOffset(4)] + public int lat_int; + + /// Longitude in WGS84 frame [degE7] + [Units("[degE7]")] + [Description("Longitude in WGS84 frame")] + //[FieldOffset(8)] + public int lon_int; + + /// Altitude (MSL, AGL or relative to home altitude, depending on frame) [m] + [Units("[m]")] + [Description("Altitude (MSL, AGL or relative to home altitude, depending on frame)")] + //[FieldOffset(12)] + public float alt; + + /// X velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("X velocity in NED frame")] + //[FieldOffset(16)] + public float vx; + + /// Y velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Y velocity in NED frame")] + //[FieldOffset(20)] + public float vy; + + /// Z velocity in NED frame [m/s] + [Units("[m/s]")] + [Description("Z velocity in NED frame")] + //[FieldOffset(24)] + public float vz; + + /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(28)] + public float afx; + + /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(32)] + public float afy; + + /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + //[FieldOffset(36)] + public float afz; + + /// yaw setpoint [rad] + [Units("[rad]")] + [Description("yaw setpoint")] + //[FieldOffset(40)] + public float yaw; + + /// yaw rate setpoint [rad/s] + [Units("[rad/s]")] + [Description("yaw rate setpoint")] + //[FieldOffset(44)] + public float yaw_rate; + + /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask [Units("")] - [Description("System ID")] - //[FieldOffset(2)] - public byte target_system; + [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] + //[FieldOffset(48)] + public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; - /// Component ID + /// Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated) MAV_FRAME [Units("")] - [Description("Component ID")] - //[FieldOffset(3)] - public byte target_component; + [Description("Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)")] + //[FieldOffset(50)] + public /*MAV_FRAME*/byte coordinate_frame; }; - /// extensions_start 1 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. - public struct mavlink_mission_current_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + public struct mavlink_local_position_ned_system_global_offset_t { /// packet ordered constructor - public mavlink_mission_current_t(ushort seq,ushort total,/*MISSION_STATE*/byte mission_state,byte mission_mode) + public mavlink_local_position_ned_system_global_offset_t(uint time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) { - this.seq = seq; - this.total = total; - this.mission_state = mission_state; - this.mission_mode = mission_mode; + this.time_boot_ms = time_boot_ms; + this.x = x; + this.y = y; + this.z = z; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; } /// packet xml order - public static mavlink_mission_current_t PopulateXMLOrder(ushort seq,ushort total,/*MISSION_STATE*/byte mission_state,byte mission_mode) + public static mavlink_local_position_ned_system_global_offset_t PopulateXMLOrder(uint time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) { - var msg = new mavlink_mission_current_t(); + var msg = new mavlink_local_position_ned_system_global_offset_t(); - msg.seq = seq; - msg.total = total; - msg.mission_state = mission_state; - msg.mission_mode = mission_mode; + msg.time_boot_ms = time_boot_ms; + msg.x = x; + msg.y = y; + msg.z = z; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; return msg; } - /// Sequence - [Units("")] - [Description("Sequence")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ushort seq; - - /// Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. - [Units("")] - [Description("Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.")] - //[FieldOffset(2)] - public ushort total; + public uint time_boot_ms; - /// Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. MISSION_STATE - [Units("")] - [Description("Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.")] + /// X Position [m] + [Units("[m]")] + [Description("X Position")] //[FieldOffset(4)] - public /*MISSION_STATE*/byte mission_state; + public float x; - /// Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). - [Units("")] - [Description("Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).")] - //[FieldOffset(5)] - public byte mission_mode; + /// Y Position [m] + [Units("[m]")] + [Description("Y Position")] + //[FieldOffset(8)] + public float y; + + /// Z Position [m] + [Units("[m]")] + [Description("Z Position")] + //[FieldOffset(12)] + public float z; + + /// Roll [rad] + [Units("[rad]")] + [Description("Roll")] + //[FieldOffset(16)] + public float roll; + + /// Pitch [rad] + [Units("[rad]")] + [Description("Pitch")] + //[FieldOffset(20)] + public float pitch; + + /// Yaw [rad] + [Units("[rad]")] + [Description("Yaw")] + //[FieldOffset(24)] + public float yaw; }; - - /// extensions_start 2 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Request the overall list of mission items from the system/component. - public struct mavlink_mission_request_list_t + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=56)] + /// Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. + public struct mavlink_hil_state_t { /// packet ordered constructor - public mavlink_mission_request_list_t(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_hil_state_t(ulong time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,short xacc,short yacc,short zacc) { - this.target_system = target_system; - this.target_component = target_component; - this.mission_type = mission_type; + this.time_usec = time_usec; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.rollspeed = rollspeed; + this.pitchspeed = pitchspeed; + this.yawspeed = yawspeed; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; } /// packet xml order - public static mavlink_mission_request_list_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_hil_state_t PopulateXMLOrder(ulong time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,short xacc,short yacc,short zacc) { - var msg = new mavlink_mission_request_list_t(); + var msg = new mavlink_hil_state_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.mission_type = mission_type; + msg.time_usec = time_usec; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.rollspeed = rollspeed; + msg.pitchspeed = pitchspeed; + msg.yawspeed = yawspeed; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; return msg; } - /// System ID - [Units("")] - [Description("System ID")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public byte target_system; + public ulong time_usec; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + /// Roll angle [rad] + [Units("[rad]")] + [Description("Roll angle")] + //[FieldOffset(8)] + public float roll; - /// Mission type. MAV_MISSION_TYPE - [Units("")] - [Description("Mission type.")] - //[FieldOffset(2)] - public /*MAV_MISSION_TYPE*/byte mission_type; + /// Pitch angle [rad] + [Units("[rad]")] + [Description("Pitch angle")] + //[FieldOffset(12)] + public float pitch; + + /// Yaw angle [rad] + [Units("[rad]")] + [Description("Yaw angle")] + //[FieldOffset(16)] + public float yaw; + + /// Body frame roll / phi angular speed [rad/s] + [Units("[rad/s]")] + [Description("Body frame roll / phi angular speed")] + //[FieldOffset(20)] + public float rollspeed; + + /// Body frame pitch / theta angular speed [rad/s] + [Units("[rad/s]")] + [Description("Body frame pitch / theta angular speed")] + //[FieldOffset(24)] + public float pitchspeed; + + /// Body frame yaw / psi angular speed [rad/s] + [Units("[rad/s]")] + [Description("Body frame yaw / psi angular speed")] + //[FieldOffset(28)] + public float yawspeed; + + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] + //[FieldOffset(32)] + public int lat; + + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] + //[FieldOffset(36)] + public int lon; + + /// Altitude [mm] + [Units("[mm]")] + [Description("Altitude")] + //[FieldOffset(40)] + public int alt; + + /// Ground X Speed (Latitude) [cm/s] + [Units("[cm/s]")] + [Description("Ground X Speed (Latitude)")] + //[FieldOffset(44)] + public short vx; + + /// Ground Y Speed (Longitude) [cm/s] + [Units("[cm/s]")] + [Description("Ground Y Speed (Longitude)")] + //[FieldOffset(46)] + public short vy; + + /// Ground Z Speed (Altitude) [cm/s] + [Units("[cm/s]")] + [Description("Ground Z Speed (Altitude)")] + //[FieldOffset(48)] + public short vz; + + /// X acceleration [mG] + [Units("[mG]")] + [Description("X acceleration")] + //[FieldOffset(50)] + public short xacc; + + /// Y acceleration [mG] + [Units("[mG]")] + [Description("Y acceleration")] + //[FieldOffset(52)] + public short yacc; + + /// Z acceleration [mG] + [Units("[mG]")] + [Description("Z acceleration")] + //[FieldOffset(54)] + public short zacc; }; - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints. - public struct mavlink_mission_count_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Sent from autopilot to simulation. Hardware in the loop control outputs + public struct mavlink_hil_controls_t { /// packet ordered constructor - public mavlink_mission_count_t(ushort count,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_hil_controls_t(ulong time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,/*MAV_MODE*/byte mode,byte nav_mode) { - this.count = count; - this.target_system = target_system; - this.target_component = target_component; - this.mission_type = mission_type; + this.time_usec = time_usec; + this.roll_ailerons = roll_ailerons; + this.pitch_elevator = pitch_elevator; + this.yaw_rudder = yaw_rudder; + this.throttle = throttle; + this.aux1 = aux1; + this.aux2 = aux2; + this.aux3 = aux3; + this.aux4 = aux4; + this.mode = mode; + this.nav_mode = nav_mode; } /// packet xml order - public static mavlink_mission_count_t PopulateXMLOrder(byte target_system,byte target_component,ushort count,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_hil_controls_t PopulateXMLOrder(ulong time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,/*MAV_MODE*/byte mode,byte nav_mode) { - var msg = new mavlink_mission_count_t(); + var msg = new mavlink_hil_controls_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.count = count; - msg.mission_type = mission_type; + msg.time_usec = time_usec; + msg.roll_ailerons = roll_ailerons; + msg.pitch_elevator = pitch_elevator; + msg.yaw_rudder = yaw_rudder; + msg.throttle = throttle; + msg.aux1 = aux1; + msg.aux2 = aux2; + msg.aux3 = aux3; + msg.aux4 = aux4; + msg.mode = mode; + msg.nav_mode = nav_mode; return msg; } - /// Number of mission items in the sequence - [Units("")] - [Description("Number of mission items in the sequence")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public ushort count; + public ulong time_usec; - /// System ID + /// Control output -1 .. 1 [Units("")] - [Description("System ID")] - //[FieldOffset(2)] - public byte target_system; + [Description("Control output -1 .. 1")] + //[FieldOffset(8)] + public float roll_ailerons; - /// Component ID + /// Control output -1 .. 1 [Units("")] - [Description("Component ID")] - //[FieldOffset(3)] - public byte target_component; + [Description("Control output -1 .. 1")] + //[FieldOffset(12)] + public float pitch_elevator; - /// Mission type. MAV_MISSION_TYPE + /// Control output -1 .. 1 [Units("")] - [Description("Mission type.")] - //[FieldOffset(4)] - public /*MAV_MISSION_TYPE*/byte mission_type; - }; + [Description("Control output -1 .. 1")] + //[FieldOffset(16)] + public float yaw_rudder; - - /// extensions_start 2 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - /// Delete all mission items at once. - public struct mavlink_mission_clear_all_t - { - /// packet ordered constructor - public mavlink_mission_clear_all_t(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) - { - this.target_system = target_system; - this.target_component = target_component; - this.mission_type = mission_type; - - } - - /// packet xml order - public static mavlink_mission_clear_all_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) - { - var msg = new mavlink_mission_clear_all_t(); + /// Throttle 0 .. 1 + [Units("")] + [Description("Throttle 0 .. 1")] + //[FieldOffset(20)] + public float throttle; - msg.target_system = target_system; - msg.target_component = target_component; - msg.mission_type = mission_type; - - return msg; - } - + /// Aux 1, -1 .. 1 + [Units("")] + [Description("Aux 1, -1 .. 1")] + //[FieldOffset(24)] + public float aux1; - /// System ID + /// Aux 2, -1 .. 1 [Units("")] - [Description("System ID")] - //[FieldOffset(0)] - public byte target_system; + [Description("Aux 2, -1 .. 1")] + //[FieldOffset(28)] + public float aux2; - /// Component ID + /// Aux 3, -1 .. 1 [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + [Description("Aux 3, -1 .. 1")] + //[FieldOffset(32)] + public float aux3; - /// Mission type. MAV_MISSION_TYPE + /// Aux 4, -1 .. 1 [Units("")] - [Description("Mission type.")] - //[FieldOffset(2)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Aux 4, -1 .. 1")] + //[FieldOffset(36)] + public float aux4; + + /// System mode. MAV_MODE + [Units("")] + [Description("System mode.")] + //[FieldOffset(40)] + public /*MAV_MODE*/byte mode; + + /// Navigation mode (MAV_NAV_MODE) + [Units("")] + [Description("Navigation mode (MAV_NAV_MODE)")] + //[FieldOffset(41)] + public byte nav_mode; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. - public struct mavlink_mission_item_reached_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + public struct mavlink_hil_rc_inputs_raw_t { /// packet ordered constructor - public mavlink_mission_item_reached_t(ushort seq) + public mavlink_hil_rc_inputs_raw_t(ulong time_usec,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,byte rssi) { - this.seq = seq; + this.time_usec = time_usec; + this.chan1_raw = chan1_raw; + this.chan2_raw = chan2_raw; + this.chan3_raw = chan3_raw; + this.chan4_raw = chan4_raw; + this.chan5_raw = chan5_raw; + this.chan6_raw = chan6_raw; + this.chan7_raw = chan7_raw; + this.chan8_raw = chan8_raw; + this.chan9_raw = chan9_raw; + this.chan10_raw = chan10_raw; + this.chan11_raw = chan11_raw; + this.chan12_raw = chan12_raw; + this.rssi = rssi; } /// packet xml order - public static mavlink_mission_item_reached_t PopulateXMLOrder(ushort seq) + public static mavlink_hil_rc_inputs_raw_t PopulateXMLOrder(ulong time_usec,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,byte rssi) { - var msg = new mavlink_mission_item_reached_t(); + var msg = new mavlink_hil_rc_inputs_raw_t(); - msg.seq = seq; + msg.time_usec = time_usec; + msg.chan1_raw = chan1_raw; + msg.chan2_raw = chan2_raw; + msg.chan3_raw = chan3_raw; + msg.chan4_raw = chan4_raw; + msg.chan5_raw = chan5_raw; + msg.chan6_raw = chan6_raw; + msg.chan7_raw = chan7_raw; + msg.chan8_raw = chan8_raw; + msg.chan9_raw = chan9_raw; + msg.chan10_raw = chan10_raw; + msg.chan11_raw = chan11_raw; + msg.chan12_raw = chan12_raw; + msg.rssi = rssi; return msg; } - /// Sequence - [Units("")] - [Description("Sequence")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public ushort seq; - }; + public ulong time_usec; - - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - /// Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). - public struct mavlink_mission_ack_t - { - /// packet ordered constructor - public mavlink_mission_ack_t(byte target_system,byte target_component,/*MAV_MISSION_RESULT*/byte type,/*MAV_MISSION_TYPE*/byte mission_type) - { - this.target_system = target_system; - this.target_component = target_component; - this.type = type; - this.mission_type = mission_type; - - } - - /// packet xml order - public static mavlink_mission_ack_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_MISSION_RESULT*/byte type,/*MAV_MISSION_TYPE*/byte mission_type) - { - var msg = new mavlink_mission_ack_t(); + /// RC channel 1 value [us] + [Units("[us]")] + [Description("RC channel 1 value")] + //[FieldOffset(8)] + public ushort chan1_raw; - msg.target_system = target_system; - msg.target_component = target_component; - msg.type = type; - msg.mission_type = mission_type; - - return msg; - } - + /// RC channel 2 value [us] + [Units("[us]")] + [Description("RC channel 2 value")] + //[FieldOffset(10)] + public ushort chan2_raw; - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(0)] - public byte target_system; + /// RC channel 3 value [us] + [Units("[us]")] + [Description("RC channel 3 value")] + //[FieldOffset(12)] + public ushort chan3_raw; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + /// RC channel 4 value [us] + [Units("[us]")] + [Description("RC channel 4 value")] + //[FieldOffset(14)] + public ushort chan4_raw; - /// Mission result. MAV_MISSION_RESULT - [Units("")] - [Description("Mission result.")] - //[FieldOffset(2)] - public /*MAV_MISSION_RESULT*/byte type; + /// RC channel 5 value [us] + [Units("[us]")] + [Description("RC channel 5 value")] + //[FieldOffset(16)] + public ushort chan5_raw; - /// Mission type. MAV_MISSION_TYPE + /// RC channel 6 value [us] + [Units("[us]")] + [Description("RC channel 6 value")] + //[FieldOffset(18)] + public ushort chan6_raw; + + /// RC channel 7 value [us] + [Units("[us]")] + [Description("RC channel 7 value")] + //[FieldOffset(20)] + public ushort chan7_raw; + + /// RC channel 8 value [us] + [Units("[us]")] + [Description("RC channel 8 value")] + //[FieldOffset(22)] + public ushort chan8_raw; + + /// RC channel 9 value [us] + [Units("[us]")] + [Description("RC channel 9 value")] + //[FieldOffset(24)] + public ushort chan9_raw; + + /// RC channel 10 value [us] + [Units("[us]")] + [Description("RC channel 10 value")] + //[FieldOffset(26)] + public ushort chan10_raw; + + /// RC channel 11 value [us] + [Units("[us]")] + [Description("RC channel 11 value")] + //[FieldOffset(28)] + public ushort chan11_raw; + + /// RC channel 12 value [us] + [Units("[us]")] + [Description("RC channel 12 value")] + //[FieldOffset(30)] + public ushort chan12_raw; + + /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. [Units("")] - [Description("Mission type.")] - //[FieldOffset(3)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(32)] + public byte rssi; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)] - /// Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor. - public struct mavlink_set_gps_global_origin_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=81)] + /// Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS) + public struct mavlink_hil_actuator_controls_t { /// packet ordered constructor - public mavlink_set_gps_global_origin_t(int latitude,int longitude,int altitude,byte target_system,ulong time_usec) + public mavlink_hil_actuator_controls_t(ulong time_usec,ulong flags,float[] controls,/*MAV_MODE_FLAG*/byte mode) { - this.latitude = latitude; - this.longitude = longitude; - this.altitude = altitude; - this.target_system = target_system; this.time_usec = time_usec; + this.flags = flags; + this.controls = controls; + this.mode = mode; } /// packet xml order - public static mavlink_set_gps_global_origin_t PopulateXMLOrder(byte target_system,int latitude,int longitude,int altitude,ulong time_usec) + public static mavlink_hil_actuator_controls_t PopulateXMLOrder(ulong time_usec,float[] controls,/*MAV_MODE_FLAG*/byte mode,ulong flags) { - var msg = new mavlink_set_gps_global_origin_t(); - - msg.target_system = target_system; - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude = altitude; - msg.time_usec = time_usec; - - return msg; - } - - - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] - //[FieldOffset(0)] - public int latitude; - - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] - //[FieldOffset(4)] - public int longitude; - - /// Altitude (MSL). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up.")] - //[FieldOffset(8)] - public int altitude; + var msg = new mavlink_hil_actuator_controls_t(); - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(12)] - public byte target_system; + msg.time_usec = time_usec; + msg.controls = controls; + msg.mode = mode; + msg.flags = flags; + + return msg; + } + /// 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. [us] [Units("[us]")] [Description("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.")] - //[FieldOffset(13)] + //[FieldOffset(0)] public ulong time_usec; + + /// Flags as bitfield, 1: indicate simulation using lockstep. bitmask + [Units("")] + [Description("Flags as bitfield, 1: indicate simulation using lockstep.")] + //[FieldOffset(8)] + public ulong flags; + + /// Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. + [Units("")] + [Description("Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public float[] controls; + + /// System mode. Includes arming state. MAV_MODE_FLAG bitmask + [Units("")] + [Description("System mode. Includes arming state.")] + //[FieldOffset(80)] + public /*MAV_MODE_FLAG*/byte mode; }; - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Publishes the GPS co-ordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message. - public struct mavlink_gps_global_origin_t + /// extensions_start 8 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] + /// Optical flow from a flow sensor (e.g. optical mouse sensor) + public struct mavlink_optical_flow_t { /// packet ordered constructor - public mavlink_gps_global_origin_t(int latitude,int longitude,int altitude,ulong time_usec) + public mavlink_optical_flow_t(ulong time_usec,float flow_comp_m_x,float flow_comp_m_y,float ground_distance,short flow_x,short flow_y,byte sensor_id,byte quality,float flow_rate_x,float flow_rate_y) { - this.latitude = latitude; - this.longitude = longitude; - this.altitude = altitude; this.time_usec = time_usec; + this.flow_comp_m_x = flow_comp_m_x; + this.flow_comp_m_y = flow_comp_m_y; + this.ground_distance = ground_distance; + this.flow_x = flow_x; + this.flow_y = flow_y; + this.sensor_id = sensor_id; + this.quality = quality; + this.flow_rate_x = flow_rate_x; + this.flow_rate_y = flow_rate_y; } /// packet xml order - public static mavlink_gps_global_origin_t PopulateXMLOrder(int latitude,int longitude,int altitude,ulong time_usec) + public static mavlink_optical_flow_t PopulateXMLOrder(ulong time_usec,byte sensor_id,short flow_x,short flow_y,float flow_comp_m_x,float flow_comp_m_y,byte quality,float ground_distance,float flow_rate_x,float flow_rate_y) { - var msg = new mavlink_gps_global_origin_t(); + var msg = new mavlink_optical_flow_t(); - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude = altitude; msg.time_usec = time_usec; + msg.sensor_id = sensor_id; + msg.flow_x = flow_x; + msg.flow_y = flow_y; + msg.flow_comp_m_x = flow_comp_m_x; + msg.flow_comp_m_y = flow_comp_m_y; + msg.quality = quality; + msg.ground_distance = ground_distance; + msg.flow_rate_x = flow_rate_x; + msg.flow_rate_y = flow_rate_y; return msg; } - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public int latitude; - - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] - //[FieldOffset(4)] - public int longitude; + public ulong time_usec; - /// Altitude (MSL). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up.")] + /// Flow in x-sensor direction, angular-speed compensated [m/s] + [Units("[m/s]")] + [Description("Flow in x-sensor direction, angular-speed compensated")] //[FieldOffset(8)] - public int altitude; + public float flow_comp_m_x; - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Flow in y-sensor direction, angular-speed compensated [m/s] + [Units("[m/s]")] + [Description("Flow in y-sensor direction, angular-speed compensated")] //[FieldOffset(12)] - public ulong time_usec; + public float flow_comp_m_y; + + /// Ground distance. Positive value: distance known. Negative value: Unknown distance [m] + [Units("[m]")] + [Description("Ground distance. Positive value: distance known. Negative value: Unknown distance")] + //[FieldOffset(16)] + public float ground_distance; + + /// 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 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; + + /// Sensor ID + [Units("")] + [Description("Sensor ID")] + //[FieldOffset(24)] + public byte sensor_id; + + /// Optical flow quality / confidence. 0: bad, 255: maximum quality + [Units("")] + [Description("Optical flow quality / confidence. 0: bad, 255: maximum quality")] + //[FieldOffset(25)] + public byte quality; + + /// Flow rate about X axis [rad/s] + [Units("[rad/s]")] + [Description("Flow rate about X axis")] + //[FieldOffset(26)] + public float flow_rate_x; + + /// Flow rate about Y axis [rad/s] + [Units("[rad/s]")] + [Description("Flow rate about Y axis")] + //[FieldOffset(30)] + public float flow_rate_y; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - /// Bind a RC channel to a parameter. The parameter should change according to the RC channel value. - public struct mavlink_param_map_rc_t + /// extensions_start 7 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=117)] + /// Global position/attitude estimate from a vision source. + public struct mavlink_global_vision_position_estimate_t { /// packet ordered constructor - public mavlink_param_map_rc_t(float param_value0,float scale,float param_value_min,float param_value_max,short param_index,byte target_system,byte target_component,byte[] param_id,byte parameter_rc_channel_index) + public mavlink_global_vision_position_estimate_t(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) { - this.param_value0 = param_value0; - this.scale = scale; - this.param_value_min = param_value_min; - this.param_value_max = param_value_max; - this.param_index = param_index; - this.target_system = target_system; - this.target_component = target_component; - this.param_id = param_id; - this.parameter_rc_channel_index = parameter_rc_channel_index; + this.usec = usec; + this.x = x; + this.y = y; + this.z = z; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.covariance = covariance; + this.reset_counter = reset_counter; } /// packet xml order - public static mavlink_param_map_rc_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,short param_index,byte parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) + public static mavlink_global_vision_position_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) { - var msg = new mavlink_param_map_rc_t(); + var msg = new mavlink_global_vision_position_estimate_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.param_id = param_id; - msg.param_index = param_index; - msg.parameter_rc_channel_index = parameter_rc_channel_index; - msg.param_value0 = param_value0; - msg.scale = scale; - msg.param_value_min = param_value_min; - msg.param_value_max = param_value_max; + msg.usec = usec; + msg.x = x; + msg.y = y; + msg.z = z; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.covariance = covariance; + msg.reset_counter = reset_counter; return msg; } - /// Initial parameter value - [Units("")] - [Description("Initial parameter value")] + /// Timestamp (UNIX time or since system boot) [us] + [Units("[us]")] + [Description("Timestamp (UNIX time or since system boot)")] //[FieldOffset(0)] - public float param_value0; - - /// Scale, maps the RC range [-1, 1] to a parameter value - [Units("")] - [Description("Scale, maps the RC range [-1, 1] to a parameter value")] - //[FieldOffset(4)] - public float scale; + public ulong usec; - /// Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - [Units("")] - [Description("Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)")] + /// Global X position [m] + [Units("[m]")] + [Description("Global X position")] //[FieldOffset(8)] - public float param_value_min; + public float x; - /// Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - [Units("")] - [Description("Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)")] + /// Global Y position [m] + [Units("[m]")] + [Description("Global Y position")] //[FieldOffset(12)] - public float param_value_max; + public float y; - /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - [Units("")] - [Description("Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.")] + /// Global Z position [m] + [Units("[m]")] + [Description("Global Z position")] //[FieldOffset(16)] - public short param_index; + public float z; - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(18)] - public byte target_system; + /// Roll angle [rad] + [Units("[rad]")] + [Description("Roll angle")] + //[FieldOffset(20)] + public float roll; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(19)] - public byte target_component; + /// Pitch angle [rad] + [Units("[rad]")] + [Description("Pitch angle")] + //[FieldOffset(24)] + public float pitch; - /// Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Yaw angle [rad] + [Units("[rad]")] + [Description("Yaw angle")] + //[FieldOffset(28)] + public float yaw; + + /// Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [Description("Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] + public float[] covariance; - /// Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. + /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. [Units("")] - [Description("Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.")] - //[FieldOffset(36)] - public byte parameter_rc_channel_index; + [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] + //[FieldOffset(116)] + public byte reset_counter; }; - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html - public struct mavlink_mission_request_int_t + /// extensions_start 7 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=117)] + /// Local position/attitude estimate from a vision source. + public struct mavlink_vision_position_estimate_t { /// packet ordered constructor - public mavlink_mission_request_int_t(ushort seq,byte target_system,byte target_component,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_vision_position_estimate_t(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) { - this.seq = seq; - this.target_system = target_system; - this.target_component = target_component; - this.mission_type = mission_type; + this.usec = usec; + this.x = x; + this.y = y; + this.z = z; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.covariance = covariance; + this.reset_counter = reset_counter; } /// packet xml order - public static mavlink_mission_request_int_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_vision_position_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) { - var msg = new mavlink_mission_request_int_t(); + var msg = new mavlink_vision_position_estimate_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.seq = seq; - msg.mission_type = mission_type; + msg.usec = usec; + msg.x = x; + msg.y = y; + msg.z = z; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.covariance = covariance; + msg.reset_counter = reset_counter; return msg; } - /// Sequence - [Units("")] - [Description("Sequence")] + /// Timestamp (UNIX time or time since system boot) [us] + [Units("[us]")] + [Description("Timestamp (UNIX time or time since system boot)")] //[FieldOffset(0)] - public ushort seq; + public ulong usec; - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(2)] - public byte target_system; + /// Local X position [m] + [Units("[m]")] + [Description("Local X position")] + //[FieldOffset(8)] + public float x; - /// Component ID + /// Local Y position [m] + [Units("[m]")] + [Description("Local Y position")] + //[FieldOffset(12)] + public float y; + + /// Local Z position [m] + [Units("[m]")] + [Description("Local Z position")] + //[FieldOffset(16)] + public float z; + + /// Roll angle [rad] + [Units("[rad]")] + [Description("Roll angle")] + //[FieldOffset(20)] + public float roll; + + /// Pitch angle [rad] + [Units("[rad]")] + [Description("Pitch angle")] + //[FieldOffset(24)] + public float pitch; + + /// Yaw angle [rad] + [Units("[rad]")] + [Description("Yaw angle")] + //[FieldOffset(28)] + public float yaw; + + /// Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Component ID")] - //[FieldOffset(3)] - public byte target_component; + [Description("Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] + public float[] covariance; - /// Mission type. MAV_MISSION_TYPE + /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. [Units("")] - [Description("Mission type.")] - //[FieldOffset(4)] - public /*MAV_MISSION_TYPE*/byte mission_type; + [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] + //[FieldOffset(116)] + public byte reset_counter; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)] - /// Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. - public struct mavlink_safety_set_allowed_area_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=57)] + /// Speed estimate from a vision source. + public struct mavlink_vision_speed_estimate_t { /// packet ordered constructor - public mavlink_safety_set_allowed_area_t(float p1x,float p1y,float p1z,float p2x,float p2y,float p2z,byte target_system,byte target_component,/*MAV_FRAME*/byte frame) + public mavlink_vision_speed_estimate_t(ulong usec,float x,float y,float z,float[] covariance,byte reset_counter) { - this.p1x = p1x; - this.p1y = p1y; - this.p1z = p1z; - this.p2x = p2x; - this.p2y = p2y; - this.p2z = p2z; - this.target_system = target_system; - this.target_component = target_component; - this.frame = frame; + this.usec = usec; + this.x = x; + this.y = y; + this.z = z; + this.covariance = covariance; + this.reset_counter = reset_counter; } /// packet xml order - public static mavlink_safety_set_allowed_area_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_FRAME*/byte frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) + public static mavlink_vision_speed_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float[] covariance,byte reset_counter) { - var msg = new mavlink_safety_set_allowed_area_t(); + var msg = new mavlink_vision_speed_estimate_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.frame = frame; - msg.p1x = p1x; - msg.p1y = p1y; - msg.p1z = p1z; - msg.p2x = p2x; - msg.p2y = p2y; - msg.p2z = p2z; + msg.usec = usec; + msg.x = x; + msg.y = y; + msg.z = z; + msg.covariance = covariance; + msg.reset_counter = reset_counter; return msg; } - /// x position 1 / Latitude 1 [m] - [Units("[m]")] - [Description("x position 1 / Latitude 1")] + /// Timestamp (UNIX time or time since system boot) [us] + [Units("[us]")] + [Description("Timestamp (UNIX time or time since system boot)")] //[FieldOffset(0)] - public float p1x; - - /// y position 1 / Longitude 1 [m] - [Units("[m]")] - [Description("y position 1 / Longitude 1")] - //[FieldOffset(4)] - public float p1y; + public ulong usec; - /// z position 1 / Altitude 1 [m] - [Units("[m]")] - [Description("z position 1 / Altitude 1")] + /// Global X speed [m/s] + [Units("[m/s]")] + [Description("Global X speed")] //[FieldOffset(8)] - public float p1z; + public float x; - /// x position 2 / Latitude 2 [m] - [Units("[m]")] - [Description("x position 2 / Latitude 2")] + /// Global Y speed [m/s] + [Units("[m/s]")] + [Description("Global Y speed")] //[FieldOffset(12)] - public float p2x; + public float y; - /// y position 2 / Longitude 2 [m] - [Units("[m]")] - [Description("y position 2 / Longitude 2")] + /// Global Z speed [m/s] + [Units("[m/s]")] + [Description("Global Z speed")] //[FieldOffset(16)] - public float p2y; - - /// z position 2 / Altitude 2 [m] - [Units("[m]")] - [Description("z position 2 / Altitude 2")] - //[FieldOffset(20)] - public float p2z; - - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(24)] - public byte target_system; + public float z; - /// Component ID + /// Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Component ID")] - //[FieldOffset(25)] - public byte target_component; + [Description("Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] + public float[] covariance; - /// Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. MAV_FRAME + /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. [Units("")] - [Description("Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.")] - //[FieldOffset(26)] - public /*MAV_FRAME*/byte frame; + [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] + //[FieldOffset(56)] + public byte reset_counter; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)] - /// Read out the safety zone the MAV currently assumes. - public struct mavlink_safety_allowed_area_t + /// extensions_start 7 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=116)] + /// Global position estimate from a Vicon motion system source. + public struct mavlink_vicon_position_estimate_t { /// packet ordered constructor - public mavlink_safety_allowed_area_t(float p1x,float p1y,float p1z,float p2x,float p2y,float p2z,/*MAV_FRAME*/byte frame) + public mavlink_vicon_position_estimate_t(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance) { - this.p1x = p1x; - this.p1y = p1y; - this.p1z = p1z; - this.p2x = p2x; - this.p2y = p2y; - this.p2z = p2z; - this.frame = frame; + this.usec = usec; + this.x = x; + this.y = y; + this.z = z; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.covariance = covariance; } /// packet xml order - public static mavlink_safety_allowed_area_t PopulateXMLOrder(/*MAV_FRAME*/byte frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) + public static mavlink_vicon_position_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance) { - var msg = new mavlink_safety_allowed_area_t(); + var msg = new mavlink_vicon_position_estimate_t(); - msg.frame = frame; - msg.p1x = p1x; - msg.p1y = p1y; - msg.p1z = p1z; - msg.p2x = p2x; - msg.p2y = p2y; - msg.p2z = p2z; + msg.usec = usec; + msg.x = x; + msg.y = y; + msg.z = z; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.covariance = covariance; return msg; } - /// x position 1 / Latitude 1 [m] - [Units("[m]")] - [Description("x position 1 / Latitude 1")] + /// Timestamp (UNIX time or time since system boot) [us] + [Units("[us]")] + [Description("Timestamp (UNIX time or time since system boot)")] //[FieldOffset(0)] - public float p1x; - - /// y position 1 / Longitude 1 [m] - [Units("[m]")] - [Description("y position 1 / Longitude 1")] - //[FieldOffset(4)] - public float p1y; + public ulong usec; - /// z position 1 / Altitude 1 [m] + /// Global X position [m] [Units("[m]")] - [Description("z position 1 / Altitude 1")] + [Description("Global X position")] //[FieldOffset(8)] - public float p1z; + public float x; - /// x position 2 / Latitude 2 [m] + /// Global Y position [m] [Units("[m]")] - [Description("x position 2 / Latitude 2")] + [Description("Global Y position")] //[FieldOffset(12)] - public float p2x; + public float y; - /// y position 2 / Longitude 2 [m] + /// Global Z position [m] [Units("[m]")] - [Description("y position 2 / Longitude 2")] + [Description("Global Z position")] //[FieldOffset(16)] - public float p2y; + public float z; - /// z position 2 / Altitude 2 [m] - [Units("[m]")] - [Description("z position 2 / Altitude 2")] + /// Roll angle [rad] + [Units("[rad]")] + [Description("Roll angle")] //[FieldOffset(20)] - public float p2z; + public float roll; - /// Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. MAV_FRAME - [Units("")] - [Description("Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.")] + /// Pitch angle [rad] + [Units("[rad]")] + [Description("Pitch angle")] //[FieldOffset(24)] - public /*MAV_FRAME*/byte frame; + public float pitch; + + /// Yaw angle [rad] + [Units("[rad]")] + [Description("Yaw angle")] + //[FieldOffset(28)] + public float yaw; + + /// Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. + [Units("")] + [Description("Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] + public float[] covariance; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=72)] - /// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - public struct mavlink_attitude_quaternion_cov_t + /// extensions_start 15 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=63)] + /// The IMU readings in SI units in NED body frame + public struct mavlink_highres_imu_t { /// packet ordered constructor - public mavlink_attitude_quaternion_cov_t(ulong time_usec,float[] q,float rollspeed,float pitchspeed,float yawspeed,float[] covariance) + public mavlink_highres_imu_t(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,ushort fields_updated,byte id) { this.time_usec = time_usec; - this.q = q; - this.rollspeed = rollspeed; - this.pitchspeed = pitchspeed; - this.yawspeed = yawspeed; - this.covariance = covariance; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.xmag = xmag; + this.ymag = ymag; + this.zmag = zmag; + this.abs_pressure = abs_pressure; + this.diff_pressure = diff_pressure; + this.pressure_alt = pressure_alt; + this.temperature = temperature; + this.fields_updated = fields_updated; + this.id = id; } /// packet xml order - public static mavlink_attitude_quaternion_cov_t PopulateXMLOrder(ulong time_usec,float[] q,float rollspeed,float pitchspeed,float yawspeed,float[] covariance) + public static mavlink_highres_imu_t PopulateXMLOrder(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,ushort fields_updated,byte id) { - var msg = new mavlink_attitude_quaternion_cov_t(); + var msg = new mavlink_highres_imu_t(); msg.time_usec = time_usec; - msg.q = q; - msg.rollspeed = rollspeed; - msg.pitchspeed = pitchspeed; - msg.yawspeed = yawspeed; - msg.covariance = covariance; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.xmag = xmag; + msg.ymag = ymag; + msg.zmag = zmag; + msg.abs_pressure = abs_pressure; + msg.diff_pressure = diff_pressure; + msg.pressure_alt = pressure_alt; + msg.temperature = temperature; + msg.fields_updated = fields_updated; + msg.id = id; return msg; } @@ -15545,163 +21684,138 @@ public static mavlink_attitude_quaternion_cov_t PopulateXMLOrder(ulong time_usec //[FieldOffset(0)] public ulong time_usec; - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)")] + /// X acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration")] //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; + public float xacc; - /// Roll angular speed [rad/s] + /// Y acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration")] + //[FieldOffset(12)] + public float yacc; + + /// Z acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration")] + //[FieldOffset(16)] + public float zacc; + + /// Angular speed around X axis [rad/s] [Units("[rad/s]")] - [Description("Roll angular speed")] + [Description("Angular speed around X axis")] + //[FieldOffset(20)] + public float xgyro; + + /// Angular speed around Y axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Y axis")] //[FieldOffset(24)] - public float rollspeed; + public float ygyro; - /// Pitch angular speed [rad/s] + /// Angular speed around Z axis [rad/s] [Units("[rad/s]")] - [Description("Pitch angular speed")] + [Description("Angular speed around Z axis")] //[FieldOffset(28)] - public float pitchspeed; + public float zgyro; - /// Yaw angular speed [rad/s] - [Units("[rad/s]")] - [Description("Yaw angular speed")] + /// X Magnetic field [gauss] + [Units("[gauss]")] + [Description("X Magnetic field")] //[FieldOffset(32)] - public float yawspeed; + public float xmag; - /// Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - [Units("")] - [Description("Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.")] + /// Y Magnetic field [gauss] + [Units("[gauss]")] + [Description("Y Magnetic field")] //[FieldOffset(36)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] - public float[] covariance; - }; - - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] - /// The state of the fixed wing navigation and position controller. - public struct mavlink_nav_controller_output_t - { - /// packet ordered constructor - public mavlink_nav_controller_output_t(float nav_roll,float nav_pitch,float alt_error,float aspd_error,float xtrack_error,short nav_bearing,short target_bearing,ushort wp_dist) - { - this.nav_roll = nav_roll; - this.nav_pitch = nav_pitch; - this.alt_error = alt_error; - this.aspd_error = aspd_error; - this.xtrack_error = xtrack_error; - this.nav_bearing = nav_bearing; - this.target_bearing = target_bearing; - this.wp_dist = wp_dist; - - } - - /// packet xml order - public static mavlink_nav_controller_output_t PopulateXMLOrder(float nav_roll,float nav_pitch,short nav_bearing,short target_bearing,ushort wp_dist,float alt_error,float aspd_error,float xtrack_error) - { - var msg = new mavlink_nav_controller_output_t(); - - msg.nav_roll = nav_roll; - msg.nav_pitch = nav_pitch; - msg.nav_bearing = nav_bearing; - msg.target_bearing = target_bearing; - msg.wp_dist = wp_dist; - msg.alt_error = alt_error; - msg.aspd_error = aspd_error; - msg.xtrack_error = xtrack_error; - - return msg; - } - - - /// Current desired roll [deg] - [Units("[deg]")] - [Description("Current desired roll")] - //[FieldOffset(0)] - public float nav_roll; + public float ymag; - /// Current desired pitch [deg] - [Units("[deg]")] - [Description("Current desired pitch")] - //[FieldOffset(4)] - public float nav_pitch; + /// Z Magnetic field [gauss] + [Units("[gauss]")] + [Description("Z Magnetic field")] + //[FieldOffset(40)] + public float zmag; - /// Current altitude error [m] - [Units("[m]")] - [Description("Current altitude error")] - //[FieldOffset(8)] - public float alt_error; + /// Absolute pressure [hPa] + [Units("[hPa]")] + [Description("Absolute pressure")] + //[FieldOffset(44)] + public float abs_pressure; - /// Current airspeed error [m/s] - [Units("[m/s]")] - [Description("Current airspeed error")] - //[FieldOffset(12)] - public float aspd_error; + /// Differential pressure [hPa] + [Units("[hPa]")] + [Description("Differential pressure")] + //[FieldOffset(48)] + public float diff_pressure; - /// Current crosstrack error on x-y plane [m] - [Units("[m]")] - [Description("Current crosstrack error on x-y plane")] - //[FieldOffset(16)] - public float xtrack_error; + /// Altitude calculated from pressure + [Units("")] + [Description("Altitude calculated from pressure")] + //[FieldOffset(52)] + public float pressure_alt; - /// Current desired heading [deg] - [Units("[deg]")] - [Description("Current desired heading")] - //[FieldOffset(20)] - public short nav_bearing; + /// Temperature [degC] + [Units("[degC]")] + [Description("Temperature")] + //[FieldOffset(56)] + public float temperature; - /// Bearing to current waypoint/target [deg] - [Units("[deg]")] - [Description("Bearing to current waypoint/target")] - //[FieldOffset(22)] - public short target_bearing; + /// Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature bitmask + [Units("")] + [Description("Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature")] + //[FieldOffset(60)] + public ushort fields_updated; - /// Distance to active waypoint [m] - [Units("[m]")] - [Description("Distance to active waypoint")] - //[FieldOffset(24)] - public ushort wp_dist; + /// Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) + [Units("")] + [Description("Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)")] + //[FieldOffset(62)] + public byte id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=181)] - /// The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. - public struct mavlink_global_position_int_cov_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) + public struct mavlink_optical_flow_rad_t { /// packet ordered constructor - public mavlink_global_position_int_cov_t(ulong time_usec,int lat,int lon,int alt,int relative_alt,float vx,float vy,float vz,float[] covariance,/*MAV_ESTIMATOR_TYPE*/byte estimator_type) + public mavlink_optical_flow_rad_t(ulong time_usec,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,uint time_delta_distance_us,float distance,short temperature,byte sensor_id,byte quality) { this.time_usec = time_usec; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.relative_alt = relative_alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.covariance = covariance; - this.estimator_type = estimator_type; + this.integration_time_us = integration_time_us; + this.integrated_x = integrated_x; + this.integrated_y = integrated_y; + this.integrated_xgyro = integrated_xgyro; + this.integrated_ygyro = integrated_ygyro; + this.integrated_zgyro = integrated_zgyro; + this.time_delta_distance_us = time_delta_distance_us; + this.distance = distance; + this.temperature = temperature; + this.sensor_id = sensor_id; + this.quality = quality; } /// packet xml order - public static mavlink_global_position_int_cov_t PopulateXMLOrder(ulong time_usec,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,int lat,int lon,int alt,int relative_alt,float vx,float vy,float vz,float[] covariance) + public static mavlink_optical_flow_rad_t PopulateXMLOrder(ulong time_usec,byte sensor_id,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,short temperature,byte quality,uint time_delta_distance_us,float distance) { - var msg = new mavlink_global_position_int_cov_t(); + var msg = new mavlink_optical_flow_rad_t(); msg.time_usec = time_usec; - msg.estimator_type = estimator_type; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.relative_alt = relative_alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.covariance = covariance; + msg.sensor_id = sensor_id; + msg.integration_time_us = integration_time_us; + msg.integrated_x = integrated_x; + msg.integrated_y = integrated_y; + msg.integrated_xgyro = integrated_xgyro; + msg.integrated_ygyro = integrated_ygyro; + msg.integrated_zgyro = integrated_zgyro; + msg.temperature = temperature; + msg.quality = quality; + msg.time_delta_distance_us = time_delta_distance_us; + msg.distance = distance; return msg; } @@ -15713,103 +21827,122 @@ public static mavlink_global_position_int_cov_t PopulateXMLOrder(ulong time_usec //[FieldOffset(0)] public ulong time_usec; - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] + /// Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. [us] + [Units("[us]")] + [Description("Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.")] //[FieldOffset(8)] - public int lat; + public uint integration_time_us; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] + /// Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) [rad] + [Units("[rad]")] + [Description("Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)")] //[FieldOffset(12)] - public int lon; + public float integrated_x; - /// Altitude in meters above MSL [mm] - [Units("[mm]")] - [Description("Altitude in meters above MSL")] + /// Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) [rad] + [Units("[rad]")] + [Description("Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)")] //[FieldOffset(16)] - public int alt; + public float integrated_y; - /// Altitude above ground [mm] - [Units("[mm]")] - [Description("Altitude above ground")] + /// RH rotation around X axis [rad] + [Units("[rad]")] + [Description("RH rotation around X axis")] //[FieldOffset(20)] - public int relative_alt; + public float integrated_xgyro; - /// Ground X Speed (Latitude) [m/s] - [Units("[m/s]")] - [Description("Ground X Speed (Latitude)")] + /// RH rotation around Y axis [rad] + [Units("[rad]")] + [Description("RH rotation around Y axis")] //[FieldOffset(24)] - public float vx; + public float integrated_ygyro; - /// Ground Y Speed (Longitude) [m/s] - [Units("[m/s]")] - [Description("Ground Y Speed (Longitude)")] + /// RH rotation around Z axis [rad] + [Units("[rad]")] + [Description("RH rotation around Z axis")] //[FieldOffset(28)] - public float vy; + public float integrated_zgyro; - /// Ground Z Speed (Altitude) [m/s] - [Units("[m/s]")] - [Description("Ground Z Speed (Altitude)")] + /// Time since the distance was sampled. [us] + [Units("[us]")] + [Description("Time since the distance was sampled.")] //[FieldOffset(32)] - public float vz; + public uint time_delta_distance_us; - /// Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - [Units("")] - [Description("Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.")] + /// Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. [m] + [Units("[m]")] + [Description("Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.")] //[FieldOffset(36)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=36)] - public float[] covariance; + public float distance; - /// Class id of the estimator this estimate originated from. MAV_ESTIMATOR_TYPE + /// Temperature [cdegC] + [Units("[cdegC]")] + [Description("Temperature")] + //[FieldOffset(40)] + public short temperature; + + /// Sensor ID [Units("")] - [Description("Class id of the estimator this estimate originated from.")] - //[FieldOffset(180)] - public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; + [Description("Sensor ID")] + //[FieldOffset(42)] + public byte sensor_id; + + /// Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + [Units("")] + [Description("Optical flow quality / confidence. 0: no valid flow, 255: maximum quality")] + //[FieldOffset(43)] + public byte quality; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=225)] - /// The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - public struct mavlink_local_position_ned_cov_t + /// extensions_start 15 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=65)] + /// The IMU readings in SI units in NED body frame + public struct mavlink_hil_sensor_t { /// packet ordered constructor - public mavlink_local_position_ned_cov_t(ulong time_usec,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,float[] covariance,/*MAV_ESTIMATOR_TYPE*/byte estimator_type) + public mavlink_hil_sensor_t(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint fields_updated,byte id) { this.time_usec = time_usec; - this.x = x; - this.y = y; - this.z = z; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.ax = ax; - this.ay = ay; - this.az = az; - this.covariance = covariance; - this.estimator_type = estimator_type; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.xmag = xmag; + this.ymag = ymag; + this.zmag = zmag; + this.abs_pressure = abs_pressure; + this.diff_pressure = diff_pressure; + this.pressure_alt = pressure_alt; + this.temperature = temperature; + this.fields_updated = fields_updated; + this.id = id; } /// packet xml order - public static mavlink_local_position_ned_cov_t PopulateXMLOrder(ulong time_usec,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,float[] covariance) + public static mavlink_hil_sensor_t PopulateXMLOrder(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint fields_updated,byte id) { - var msg = new mavlink_local_position_ned_cov_t(); + var msg = new mavlink_hil_sensor_t(); msg.time_usec = time_usec; - msg.estimator_type = estimator_type; - msg.x = x; - msg.y = y; - msg.z = z; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.ax = ax; - msg.ay = ay; - msg.az = az; - msg.covariance = covariance; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.xmag = xmag; + msg.ymag = ymag; + msg.zmag = zmag; + msg.abs_pressure = abs_pressure; + msg.diff_pressure = diff_pressure; + msg.pressure_alt = pressure_alt; + msg.temperature = temperature; + msg.fields_updated = fields_updated; + msg.id = id; return msg; } @@ -15821,1263 +21954,970 @@ public static mavlink_local_position_ned_cov_t PopulateXMLOrder(ulong time_usec, //[FieldOffset(0)] public ulong time_usec; - /// X Position [m] - [Units("[m]")] - [Description("X Position")] + /// X acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration")] //[FieldOffset(8)] - public float x; + public float xacc; - /// Y Position [m] - [Units("[m]")] - [Description("Y Position")] + /// Y acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration")] //[FieldOffset(12)] - public float y; + public float yacc; - /// Z Position [m] - [Units("[m]")] - [Description("Z Position")] + /// Z acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration")] //[FieldOffset(16)] - public float z; + public float zacc; - /// X Speed [m/s] - [Units("[m/s]")] - [Description("X Speed")] + /// Angular speed around X axis in body frame [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around X axis in body frame")] //[FieldOffset(20)] - public float vx; + public float xgyro; - /// Y Speed [m/s] - [Units("[m/s]")] - [Description("Y Speed")] + /// Angular speed around Y axis in body frame [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Y axis in body frame")] //[FieldOffset(24)] - public float vy; + public float ygyro; - /// Z Speed [m/s] - [Units("[m/s]")] - [Description("Z Speed")] + /// Angular speed around Z axis in body frame [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Z axis in body frame")] //[FieldOffset(28)] - public float vz; + public float zgyro; - /// X Acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("X Acceleration")] + /// X Magnetic field [gauss] + [Units("[gauss]")] + [Description("X Magnetic field")] //[FieldOffset(32)] - public float ax; + public float xmag; - /// Y Acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Y Acceleration")] + /// Y Magnetic field [gauss] + [Units("[gauss]")] + [Description("Y Magnetic field")] //[FieldOffset(36)] - public float ay; + public float ymag; - /// Z Acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Z Acceleration")] + /// Z Magnetic field [gauss] + [Units("[gauss]")] + [Description("Z Magnetic field")] //[FieldOffset(40)] - public float az; + public float zmag; - /// Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - [Units("")] - [Description("Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.")] + /// Absolute pressure [hPa] + [Units("[hPa]")] + [Description("Absolute pressure")] //[FieldOffset(44)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=45)] - public float[] covariance; + public float abs_pressure; - /// Class id of the estimator this estimate originated from. MAV_ESTIMATOR_TYPE + /// Differential pressure (airspeed) [hPa] + [Units("[hPa]")] + [Description("Differential pressure (airspeed)")] + //[FieldOffset(48)] + public float diff_pressure; + + /// Altitude calculated from pressure [Units("")] - [Description("Class id of the estimator this estimate originated from.")] - //[FieldOffset(224)] - public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; + [Description("Altitude calculated from pressure")] + //[FieldOffset(52)] + public float pressure_alt; + + /// Temperature [degC] + [Units("[degC]")] + [Description("Temperature")] + //[FieldOffset(56)] + public float temperature; + + /// Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. bitmask + [Units("")] + [Description("Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.")] + //[FieldOffset(60)] + public uint fields_updated; + + /// Sensor ID (zero indexed). Used for multiple sensor inputs + [Units("")] + [Description("Sensor ID (zero indexed). Used for multiple sensor inputs")] + //[FieldOffset(64)] + public byte id; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification. - public struct mavlink_rc_channels_t + /// 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_rc_channels_t(uint time_boot_ms,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw,byte chancount,byte rssi) + 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.time_boot_ms = time_boot_ms; - this.chan1_raw = chan1_raw; - this.chan2_raw = chan2_raw; - this.chan3_raw = chan3_raw; - this.chan4_raw = chan4_raw; - this.chan5_raw = chan5_raw; - this.chan6_raw = chan6_raw; - this.chan7_raw = chan7_raw; - this.chan8_raw = chan8_raw; - this.chan9_raw = chan9_raw; - this.chan10_raw = chan10_raw; - this.chan11_raw = chan11_raw; - this.chan12_raw = chan12_raw; - this.chan13_raw = chan13_raw; - this.chan14_raw = chan14_raw; - this.chan15_raw = chan15_raw; - this.chan16_raw = chan16_raw; - this.chan17_raw = chan17_raw; - this.chan18_raw = chan18_raw; - this.chancount = chancount; - this.rssi = rssi; + this.q1 = q1; + this.q2 = q2; + this.q3 = q3; + this.q4 = q4; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.std_dev_horz = std_dev_horz; + this.std_dev_vert = std_dev_vert; + 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_rc_channels_t PopulateXMLOrder(uint time_boot_ms,byte chancount,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw,byte rssi) + 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_rc_channels_t(); + var msg = new mavlink_sim_state_t(); - msg.time_boot_ms = time_boot_ms; - msg.chancount = chancount; - msg.chan1_raw = chan1_raw; - msg.chan2_raw = chan2_raw; - msg.chan3_raw = chan3_raw; - msg.chan4_raw = chan4_raw; - msg.chan5_raw = chan5_raw; - msg.chan6_raw = chan6_raw; - msg.chan7_raw = chan7_raw; - msg.chan8_raw = chan8_raw; - msg.chan9_raw = chan9_raw; - msg.chan10_raw = chan10_raw; - msg.chan11_raw = chan11_raw; - msg.chan12_raw = chan12_raw; - msg.chan13_raw = chan13_raw; - msg.chan14_raw = chan14_raw; - msg.chan15_raw = chan15_raw; - msg.chan16_raw = chan16_raw; - msg.chan17_raw = chan17_raw; - msg.chan18_raw = chan18_raw; - msg.rssi = rssi; + msg.q1 = q1; + msg.q2 = q2; + msg.q3 = q3; + msg.q4 = q4; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.std_dev_horz = std_dev_horz; + msg.std_dev_vert = std_dev_vert; + msg.vn = vn; + msg.ve = ve; + msg.vd = vd; + msg.lat_int = lat_int; + msg.lon_int = lon_int; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// True attitude quaternion component 1, w (1 in null-rotation) + [Units("")] + [Description("True attitude quaternion component 1, w (1 in null-rotation)")] //[FieldOffset(0)] - public uint time_boot_ms; + public float q1; - /// RC channel 1 value. [us] - [Units("[us]")] - [Description("RC channel 1 value.")] + /// True attitude quaternion component 2, x (0 in null-rotation) + [Units("")] + [Description("True attitude quaternion component 2, x (0 in null-rotation)")] //[FieldOffset(4)] - public ushort chan1_raw; - - /// RC channel 2 value. [us] - [Units("[us]")] - [Description("RC channel 2 value.")] - //[FieldOffset(6)] - public ushort chan2_raw; + public float q2; - /// RC channel 3 value. [us] - [Units("[us]")] - [Description("RC channel 3 value.")] + /// True attitude quaternion component 3, y (0 in null-rotation) + [Units("")] + [Description("True attitude quaternion component 3, y (0 in null-rotation)")] //[FieldOffset(8)] - public ushort chan3_raw; - - /// RC channel 4 value. [us] - [Units("[us]")] - [Description("RC channel 4 value.")] - //[FieldOffset(10)] - public ushort chan4_raw; + public float q3; - /// RC channel 5 value. [us] - [Units("[us]")] - [Description("RC channel 5 value.")] + /// True attitude quaternion component 4, z (0 in null-rotation) + [Units("")] + [Description("True attitude quaternion component 4, z (0 in null-rotation)")] //[FieldOffset(12)] - public ushort chan5_raw; - - /// RC channel 6 value. [us] - [Units("[us]")] - [Description("RC channel 6 value.")] - //[FieldOffset(14)] - public ushort chan6_raw; + public float q4; - /// RC channel 7 value. [us] - [Units("[us]")] - [Description("RC channel 7 value.")] + /// Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + [Units("")] + [Description("Attitude roll expressed as Euler angles, not recommended except for human-readable outputs")] //[FieldOffset(16)] - public ushort chan7_raw; - - /// RC channel 8 value. [us] - [Units("[us]")] - [Description("RC channel 8 value.")] - //[FieldOffset(18)] - public ushort chan8_raw; + public float roll; - /// RC channel 9 value. [us] - [Units("[us]")] - [Description("RC channel 9 value.")] + /// Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + [Units("")] + [Description("Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs")] //[FieldOffset(20)] - public ushort chan9_raw; - - /// RC channel 10 value. [us] - [Units("[us]")] - [Description("RC channel 10 value.")] - //[FieldOffset(22)] - public ushort chan10_raw; + public float pitch; - /// RC channel 11 value. [us] - [Units("[us]")] - [Description("RC channel 11 value.")] + /// Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + [Units("")] + [Description("Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs")] //[FieldOffset(24)] - public ushort chan11_raw; - - /// RC channel 12 value. [us] - [Units("[us]")] - [Description("RC channel 12 value.")] - //[FieldOffset(26)] - public ushort chan12_raw; + public float yaw; - /// RC channel 13 value. [us] - [Units("[us]")] - [Description("RC channel 13 value.")] + /// X acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration")] //[FieldOffset(28)] - public ushort chan13_raw; - - /// RC channel 14 value. [us] - [Units("[us]")] - [Description("RC channel 14 value.")] - //[FieldOffset(30)] - public ushort chan14_raw; + public float xacc; - /// RC channel 15 value. [us] - [Units("[us]")] - [Description("RC channel 15 value.")] + /// Y acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration")] //[FieldOffset(32)] - public ushort chan15_raw; - - /// RC channel 16 value. [us] - [Units("[us]")] - [Description("RC channel 16 value.")] - //[FieldOffset(34)] - public ushort chan16_raw; + public float yacc; - /// RC channel 17 value. [us] - [Units("[us]")] - [Description("RC channel 17 value.")] + /// Z acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration")] //[FieldOffset(36)] - public ushort chan17_raw; - - /// RC channel 18 value. [us] - [Units("[us]")] - [Description("RC channel 18 value.")] - //[FieldOffset(38)] - public ushort chan18_raw; + public float zacc; - /// Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - [Units("")] - [Description("Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.")] + /// Angular speed around X axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around X axis")] //[FieldOffset(40)] - public byte chancount; - - /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. - [Units("")] - [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(41)] - public byte rssi; - }; + public float xgyro; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Request a data stream. - public struct mavlink_request_data_stream_t - { - /// packet ordered constructor - public mavlink_request_data_stream_t(ushort req_message_rate,byte target_system,byte target_component,byte req_stream_id,byte start_stop) - { - this.req_message_rate = req_message_rate; - this.target_system = target_system; - this.target_component = target_component; - this.req_stream_id = req_stream_id; - this.start_stop = start_stop; - - } - - /// packet xml order - public static mavlink_request_data_stream_t PopulateXMLOrder(byte target_system,byte target_component,byte req_stream_id,ushort req_message_rate,byte start_stop) - { - var msg = new mavlink_request_data_stream_t(); + /// Angular speed around Y axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Y axis")] + //[FieldOffset(44)] + public float ygyro; - msg.target_system = target_system; - msg.target_component = target_component; - msg.req_stream_id = req_stream_id; - msg.req_message_rate = req_message_rate; - msg.start_stop = start_stop; - - return msg; - } - + /// Angular speed around Z axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Z axis")] + //[FieldOffset(48)] + public float zgyro; - /// The requested message rate [Hz] - [Units("[Hz]")] - [Description("The requested message rate")] - //[FieldOffset(0)] - public ushort req_message_rate; + /// Latitude [deg] + [Units("[deg]")] + [Description("Latitude")] + //[FieldOffset(52)] + public float lat; - /// The target requested to send the message stream. - [Units("")] - [Description("The target requested to send the message stream.")] - //[FieldOffset(2)] - public byte target_system; + /// Longitude [deg] + [Units("[deg]")] + [Description("Longitude")] + //[FieldOffset(56)] + public float lon; - /// The target requested to send the message stream. - [Units("")] - [Description("The target requested to send the message stream.")] - //[FieldOffset(3)] - public byte target_component; + /// Altitude [m] + [Units("[m]")] + [Description("Altitude")] + //[FieldOffset(60)] + public float alt; - /// The ID of the requested data stream + /// Horizontal position standard deviation [Units("")] - [Description("The ID of the requested data stream")] - //[FieldOffset(4)] - public byte req_stream_id; + [Description("Horizontal position standard deviation")] + //[FieldOffset(64)] + public float std_dev_horz; - /// 1 to start sending, 0 to stop sending. + /// Vertical position standard deviation [Units("")] - [Description("1 to start sending, 0 to stop sending.")] - //[FieldOffset(5)] - public byte start_stop; - }; + [Description("Vertical position standard deviation")] + //[FieldOffset(68)] + public float std_dev_vert; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - /// Data stream status information. - public struct mavlink_data_stream_t - { - /// packet ordered constructor - public mavlink_data_stream_t(ushort message_rate,byte stream_id,byte on_off) - { - this.message_rate = message_rate; - this.stream_id = stream_id; - this.on_off = on_off; - - } - - /// packet xml order - public static mavlink_data_stream_t PopulateXMLOrder(byte stream_id,ushort message_rate,byte on_off) - { - var msg = new mavlink_data_stream_t(); + /// True velocity in north direction in earth-fixed NED frame [m/s] + [Units("[m/s]")] + [Description("True velocity in north direction in earth-fixed NED frame")] + //[FieldOffset(72)] + public float vn; - msg.stream_id = stream_id; - msg.message_rate = message_rate; - msg.on_off = on_off; - - return msg; - } - + /// True velocity in east direction in earth-fixed NED frame [m/s] + [Units("[m/s]")] + [Description("True velocity in east direction in earth-fixed NED frame")] + //[FieldOffset(76)] + public float ve; - /// The message rate [Hz] - [Units("[Hz]")] - [Description("The message rate")] - //[FieldOffset(0)] - public ushort message_rate; + /// True velocity in down direction in earth-fixed NED frame [m/s] + [Units("[m/s]")] + [Description("True velocity in down direction in earth-fixed NED frame")] + //[FieldOffset(80)] + public float vd; - /// The ID of the requested data stream - [Units("")] - [Description("The ID of the requested data stream")] - //[FieldOffset(2)] - public byte stream_id; + /// 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; - /// 1 stream is enabled, 0 stream is stopped. - [Units("")] - [Description("1 stream is enabled, 0 stream is stopped.")] - //[FieldOffset(3)] - public byte on_off; + /// 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; }; - /// 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 + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Status generated by radio and injected into MAVLink stream. + public struct mavlink_radio_status_t { /// packet ordered constructor - 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) + public mavlink_radio_status_t(ushort rxerrors,ushort @fixed,byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise) { - this.x = x; - this.y = y; - this.z = z; - 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; + this.rxerrors = rxerrors; + this.@fixed = @fixed; + this.rssi = rssi; + this.remrssi = remrssi; + this.txbuf = txbuf; + this.noise = noise; + this.remnoise = remnoise; } /// packet xml order - 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) + public static mavlink_radio_status_t PopulateXMLOrder(byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise,ushort rxerrors,ushort @fixed) { - var msg = new mavlink_manual_control_t(); + var msg = new mavlink_radio_status_t(); - msg.target = target; - msg.x = x; - msg.y = y; - 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; + msg.rssi = rssi; + msg.remrssi = remrssi; + msg.txbuf = txbuf; + msg.noise = noise; + msg.remnoise = remnoise; + msg.rxerrors = rxerrors; + msg.@fixed = @fixed; return msg; } - /// X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + /// Count of radio packet receive errors (since boot). [Units("")] - [Description("X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.")] + [Description("Count of radio packet receive errors (since boot).")] //[FieldOffset(0)] - public short x; + public ushort rxerrors; - /// Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + /// Count of error corrected radio packets (since boot). [Units("")] - [Description("Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.")] + [Description("Count of error corrected radio packets (since boot).")] //[FieldOffset(2)] - public short y; + public ushort @fixed; - /// 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. + /// Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. [Units("")] - [Description("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.")] + [Description("Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] //[FieldOffset(4)] - public short z; - - /// 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. - [Units("")] - [Description("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.")] - //[FieldOffset(6)] - public short r; - - /// A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - [Units("")] - [Description("A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.")] - //[FieldOffset(8)] - public ushort buttons; - - /// The system to be controlled. - [Units("")] - [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; + public byte rssi; - /// 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. + /// Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. [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; + [Description("Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(5)] + public byte remrssi; - /// 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; + /// Remaining free transmitter buffer space. [%] + [Units("[%]")] + [Description("Remaining free transmitter buffer space.")] + //[FieldOffset(6)] + public byte txbuf; - /// 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. + /// Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. [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; + [Description("Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(7)] + public byte noise; - /// 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. + /// Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. [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; + [Description("Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.")] + //[FieldOffset(8)] + public byte remnoise; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] - /// 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 - public struct mavlink_rc_channels_override_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=254)] + /// File transfer message + public struct mavlink_file_transfer_protocol_t { /// packet ordered constructor - public mavlink_rc_channels_override_t(ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,byte target_system,byte target_component,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw) + public mavlink_file_transfer_protocol_t(byte target_network,byte target_system,byte target_component,byte[] payload) { - this.chan1_raw = chan1_raw; - this.chan2_raw = chan2_raw; - this.chan3_raw = chan3_raw; - this.chan4_raw = chan4_raw; - this.chan5_raw = chan5_raw; - this.chan6_raw = chan6_raw; - this.chan7_raw = chan7_raw; - this.chan8_raw = chan8_raw; + this.target_network = target_network; this.target_system = target_system; this.target_component = target_component; - this.chan9_raw = chan9_raw; - this.chan10_raw = chan10_raw; - this.chan11_raw = chan11_raw; - this.chan12_raw = chan12_raw; - this.chan13_raw = chan13_raw; - this.chan14_raw = chan14_raw; - this.chan15_raw = chan15_raw; - this.chan16_raw = chan16_raw; - this.chan17_raw = chan17_raw; - this.chan18_raw = chan18_raw; + this.payload = payload; } /// packet xml order - public static mavlink_rc_channels_override_t PopulateXMLOrder(byte target_system,byte target_component,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,ushort chan13_raw,ushort chan14_raw,ushort chan15_raw,ushort chan16_raw,ushort chan17_raw,ushort chan18_raw) + public static mavlink_file_transfer_protocol_t PopulateXMLOrder(byte target_network,byte target_system,byte target_component,byte[] payload) { - var msg = new mavlink_rc_channels_override_t(); + var msg = new mavlink_file_transfer_protocol_t(); + msg.target_network = target_network; msg.target_system = target_system; msg.target_component = target_component; - msg.chan1_raw = chan1_raw; - msg.chan2_raw = chan2_raw; - msg.chan3_raw = chan3_raw; - msg.chan4_raw = chan4_raw; - msg.chan5_raw = chan5_raw; - msg.chan6_raw = chan6_raw; - msg.chan7_raw = chan7_raw; - msg.chan8_raw = chan8_raw; - msg.chan9_raw = chan9_raw; - msg.chan10_raw = chan10_raw; - msg.chan11_raw = chan11_raw; - msg.chan12_raw = chan12_raw; - msg.chan13_raw = chan13_raw; - msg.chan14_raw = chan14_raw; - msg.chan15_raw = chan15_raw; - msg.chan16_raw = chan16_raw; - msg.chan17_raw = chan17_raw; - msg.chan18_raw = chan18_raw; + msg.payload = payload; return msg; } - /// RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] + /// Network ID (0 for broadcast) + [Units("")] + [Description("Network ID (0 for broadcast)")] //[FieldOffset(0)] - public ushort chan1_raw; - - /// RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(2)] - public ushort chan2_raw; - - /// RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(4)] - public ushort chan3_raw; - - /// RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(6)] - public ushort chan4_raw; - - /// RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(8)] - public ushort chan5_raw; - - /// RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(10)] - public ushort chan6_raw; - - /// RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(12)] - public ushort chan7_raw; - - /// RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.")] - //[FieldOffset(14)] - public ushort chan8_raw; + public byte target_network; - /// System ID + /// System ID (0 for broadcast) [Units("")] - [Description("System ID")] - //[FieldOffset(16)] + [Description("System ID (0 for broadcast)")] + //[FieldOffset(1)] public byte target_system; - /// Component ID + /// Component ID (0 for broadcast) [Units("")] - [Description("Component ID")] - //[FieldOffset(17)] + [Description("Component ID (0 for broadcast)")] + //[FieldOffset(2)] public byte target_component; - /// RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(18)] - public ushort chan9_raw; - - /// RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(20)] - public ushort chan10_raw; - - /// RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(22)] - public ushort chan11_raw; - - /// RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(24)] - public ushort chan12_raw; - - /// RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(26)] - public ushort chan13_raw; - - /// RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(28)] - public ushort chan14_raw; - - /// RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(30)] - public ushort chan15_raw; - - /// RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(32)] - public ushort chan16_raw; - - /// RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(34)] - public ushort chan17_raw; - - /// RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. [us] - [Units("[us]")] - [Description("RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.")] - //[FieldOffset(36)] - public ushort chan18_raw; + /// Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + [Units("")] + [Description("Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.")] + //[FieldOffset(3)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=251)] + public byte[] payload; }; - /// extensions_start 14 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] - /// Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html. - public struct mavlink_mission_item_int_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Time synchronization message. + public struct mavlink_timesync_t { /// packet ordered constructor - public mavlink_mission_item_int_t(float param1,float param2,float param3,float param4,int x,int y,float z,ushort seq,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue,/*MAV_MISSION_TYPE*/byte mission_type) + public mavlink_timesync_t(long tc1,long ts1) { - this.param1 = param1; - this.param2 = param2; - this.param3 = param3; - this.param4 = param4; - this.x = x; - this.y = y; - this.z = z; - this.seq = seq; - this.command = command; - this.target_system = target_system; - this.target_component = target_component; - this.frame = frame; - this.current = current; - this.autocontinue = autocontinue; - this.mission_type = mission_type; + this.tc1 = tc1; + this.ts1 = ts1; } /// packet xml order - public static mavlink_mission_item_int_t PopulateXMLOrder(byte target_system,byte target_component,ushort seq,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,int x,int y,float z,/*MAV_MISSION_TYPE*/byte mission_type) + public static mavlink_timesync_t PopulateXMLOrder(long tc1,long ts1) { - var msg = new mavlink_mission_item_int_t(); + var msg = new mavlink_timesync_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.seq = seq; - msg.frame = frame; - msg.command = command; - msg.current = current; - msg.autocontinue = autocontinue; - msg.param1 = param1; - msg.param2 = param2; - msg.param3 = param3; - msg.param4 = param4; - msg.x = x; - msg.y = y; - msg.z = z; - msg.mission_type = mission_type; + msg.tc1 = tc1; + msg.ts1 = ts1; return msg; } - /// PARAM1, see MAV_CMD enum + /// Time sync timestamp 1 [Units("")] - [Description("PARAM1, see MAV_CMD enum")] + [Description("Time sync timestamp 1")] //[FieldOffset(0)] - public float param1; - - /// PARAM2, see MAV_CMD enum - [Units("")] - [Description("PARAM2, see MAV_CMD enum")] - //[FieldOffset(4)] - public float param2; + public long tc1; - /// PARAM3, see MAV_CMD enum + /// Time sync timestamp 2 [Units("")] - [Description("PARAM3, see MAV_CMD enum")] + [Description("Time sync timestamp 2")] //[FieldOffset(8)] - public float param3; - - /// PARAM4, see MAV_CMD enum - [Units("")] - [Description("PARAM4, see MAV_CMD enum")] - //[FieldOffset(12)] - public float param4; - - /// PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - [Units("")] - [Description("PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7")] - //[FieldOffset(16)] - public int x; - - /// PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - [Units("")] - [Description("PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7")] - //[FieldOffset(20)] - public int y; - - /// PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - [Units("")] - [Description("PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.")] - //[FieldOffset(24)] - public float z; - - /// Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - [Units("")] - [Description("Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).")] - //[FieldOffset(28)] - public ushort seq; - - /// The scheduled action for the waypoint. MAV_CMD - [Units("")] - [Description("The scheduled action for the waypoint.")] - //[FieldOffset(30)] - public /*MAV_CMD*/ushort command; - - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(32)] - public byte target_system; - - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(33)] - public byte target_component; - - /// The coordinate system of the waypoint. MAV_FRAME - [Units("")] - [Description("The coordinate system of the waypoint.")] - //[FieldOffset(34)] - public /*MAV_FRAME*/byte frame; - - /// false:0, true:1 - [Units("")] - [Description("false:0, true:1")] - //[FieldOffset(35)] - public byte current; - - /// Autocontinue to next waypoint - [Units("")] - [Description("Autocontinue to next waypoint")] - //[FieldOffset(36)] - public byte autocontinue; - - /// Mission type. MAV_MISSION_TYPE - [Units("")] - [Description("Mission type.")] - //[FieldOffset(37)] - public /*MAV_MISSION_TYPE*/byte mission_type; + public long ts1; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Metrics typically displayed on a HUD for fixed wing aircraft. - public struct mavlink_vfr_hud_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// Camera-IMU triggering and synchronisation message. + public struct mavlink_camera_trigger_t { /// packet ordered constructor - public mavlink_vfr_hud_t(float airspeed,float groundspeed,float alt,float climb,short heading,ushort throttle) + public mavlink_camera_trigger_t(ulong time_usec,uint seq) { - this.airspeed = airspeed; - this.groundspeed = groundspeed; - this.alt = alt; - this.climb = climb; - this.heading = heading; - this.throttle = throttle; + this.time_usec = time_usec; + this.seq = seq; } /// packet xml order - public static mavlink_vfr_hud_t PopulateXMLOrder(float airspeed,float groundspeed,short heading,ushort throttle,float alt,float climb) + public static mavlink_camera_trigger_t PopulateXMLOrder(ulong time_usec,uint seq) { - var msg = new mavlink_vfr_hud_t(); + var msg = new mavlink_camera_trigger_t(); - msg.airspeed = airspeed; - msg.groundspeed = groundspeed; - msg.heading = heading; - msg.throttle = throttle; - msg.alt = alt; - msg.climb = climb; + msg.time_usec = time_usec; + msg.seq = seq; return msg; } - /// Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. [m/s] - [Units("[m/s]")] - [Description("Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.")] + /// Timestamp for image frame (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. [us] + [Units("[us]")] + [Description("Timestamp for image frame (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.")] //[FieldOffset(0)] - public float airspeed; - - /// Current ground speed. [m/s] - [Units("[m/s]")] - [Description("Current ground speed.")] - //[FieldOffset(4)] - public float groundspeed; + public ulong time_usec; - /// Current altitude (MSL). [m] - [Units("[m]")] - [Description("Current altitude (MSL).")] + /// Image frame sequence + [Units("")] + [Description("Image frame sequence")] //[FieldOffset(8)] - public float alt; - - /// Current climb rate. [m/s] - [Units("[m/s]")] - [Description("Current climb rate.")] - //[FieldOffset(12)] - public float climb; - - /// Current heading in compass units (0-360, 0=north). [deg] - [Units("[deg]")] - [Description("Current heading in compass units (0-360, 0=north).")] - //[FieldOffset(16)] - public short heading; - - /// Current throttle setting (0 to 100). [%] - [Units("[%]")] - [Description("Current throttle setting (0 to 100).")] - //[FieldOffset(18)] - public ushort throttle; + public uint seq; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] - /// Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. The command microservice is documented at https://mavlink.io/en/services/command.html - public struct mavlink_command_int_t + /// extensions_start 13 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=39)] + /// The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. + public struct mavlink_hil_gps_t { /// packet ordered constructor - public mavlink_command_int_t(float param1,float param2,float param3,float param4,int x,int y,float z,/*MAV_CMD*/ushort command,byte target_system,byte target_component,/*MAV_FRAME*/byte frame,byte current,byte autocontinue) + public mavlink_hil_gps_t(ulong time_usec,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,short vn,short ve,short vd,ushort cog,byte fix_type,byte satellites_visible,byte id,ushort yaw) { - this.param1 = param1; - this.param2 = param2; - this.param3 = param3; - this.param4 = param4; - this.x = x; - this.y = y; - this.z = z; - this.command = command; - this.target_system = target_system; - this.target_component = target_component; - this.frame = frame; - this.current = current; - this.autocontinue = autocontinue; + this.time_usec = time_usec; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.eph = eph; + this.epv = epv; + this.vel = vel; + this.vn = vn; + this.ve = ve; + this.vd = vd; + this.cog = cog; + this.fix_type = fix_type; + this.satellites_visible = satellites_visible; + this.id = id; + this.yaw = yaw; } /// packet xml order - public static mavlink_command_int_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_FRAME*/byte frame,/*MAV_CMD*/ushort command,byte current,byte autocontinue,float param1,float param2,float param3,float param4,int x,int y,float z) + public static mavlink_hil_gps_t PopulateXMLOrder(ulong time_usec,byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,short vn,short ve,short vd,ushort cog,byte satellites_visible,byte id,ushort yaw) { - var msg = new mavlink_command_int_t(); + var msg = new mavlink_hil_gps_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.frame = frame; - msg.command = command; - msg.current = current; - msg.autocontinue = autocontinue; - msg.param1 = param1; - msg.param2 = param2; - msg.param3 = param3; - msg.param4 = param4; - msg.x = x; - msg.y = y; - msg.z = z; + msg.time_usec = time_usec; + msg.fix_type = fix_type; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.eph = eph; + msg.epv = epv; + msg.vel = vel; + msg.vn = vn; + msg.ve = ve; + msg.vd = vd; + msg.cog = cog; + msg.satellites_visible = satellites_visible; + msg.id = id; + msg.yaw = yaw; return msg; } - /// PARAM1, see MAV_CMD enum - [Units("")] - [Description("PARAM1, see MAV_CMD enum")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public float param1; - - /// PARAM2, see MAV_CMD enum - [Units("")] - [Description("PARAM2, see MAV_CMD enum")] - //[FieldOffset(4)] - public float param2; + public ulong time_usec; - /// PARAM3, see MAV_CMD enum - [Units("")] - [Description("PARAM3, see MAV_CMD enum")] + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] //[FieldOffset(8)] - public float param3; + public int lat; - /// PARAM4, see MAV_CMD enum - [Units("")] - [Description("PARAM4, see MAV_CMD enum")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] //[FieldOffset(12)] - public float param4; + public int lon; - /// PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - [Units("")] - [Description("PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7")] + /// Altitude (MSL). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Positive for up.")] //[FieldOffset(16)] - public int x; + public int alt; - /// PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX [Units("")] - [Description("PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7")] + [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] //[FieldOffset(20)] - public int y; + public ushort eph; - /// PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). + /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX [Units("")] - [Description("PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).")] + [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + //[FieldOffset(22)] + public ushort epv; + + /// GPS ground speed. If unknown, set to: 65535 [cm/s] + [Units("[cm/s]")] + [Description("GPS ground speed. If unknown, set to: 65535")] //[FieldOffset(24)] - public float z; + public ushort vel; - /// The scheduled action for the mission item. MAV_CMD - [Units("")] - [Description("The scheduled action for the mission item.")] + /// GPS velocity in north direction in earth-fixed NED frame [cm/s] + [Units("[cm/s]")] + [Description("GPS velocity in north direction in earth-fixed NED frame")] + //[FieldOffset(26)] + public short vn; + + /// GPS velocity in east direction in earth-fixed NED frame [cm/s] + [Units("[cm/s]")] + [Description("GPS velocity in east direction in earth-fixed NED frame")] //[FieldOffset(28)] - public /*MAV_CMD*/ushort command; + public short ve; - /// System ID - [Units("")] - [Description("System ID")] + /// GPS velocity in down direction in earth-fixed NED frame [cm/s] + [Units("[cm/s]")] + [Description("GPS velocity in down direction in earth-fixed NED frame")] //[FieldOffset(30)] - public byte target_system; + public short vd; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(31)] - public byte target_component; + /// Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535 [cdeg] + [Units("[cdeg]")] + [Description("Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535")] + //[FieldOffset(32)] + public ushort cog; - /// The coordinate system of the COMMAND. MAV_FRAME + /// 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. [Units("")] - [Description("The coordinate system of the COMMAND.")] - //[FieldOffset(32)] - public /*MAV_FRAME*/byte frame; + [Description("0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.")] + //[FieldOffset(34)] + public byte fix_type; - /// Not used. + /// Number of satellites visible. If unknown, set to 255 [Units("")] - [Description("Not used.")] - //[FieldOffset(33)] - public byte current; + [Description("Number of satellites visible. If unknown, set to 255")] + //[FieldOffset(35)] + public byte satellites_visible; - /// Not used (set 0). + /// GPS ID (zero indexed). Used for multiple GPS inputs [Units("")] - [Description("Not used (set 0).")] - //[FieldOffset(34)] - public byte autocontinue; + [Description("GPS ID (zero indexed). Used for multiple GPS inputs")] + //[FieldOffset(36)] + public byte id; + + /// Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north [cdeg] + [Units("[cdeg]")] + [Description("Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north")] + //[FieldOffset(37)] + public ushort yaw; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] - /// Send a command with up to seven parameters to the MAV. The command microservice is documented at https://mavlink.io/en/services/command.html - public struct mavlink_command_long_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) + public struct mavlink_hil_optical_flow_t { /// packet ordered constructor - public mavlink_command_long_t(float param1,float param2,float param3,float param4,float param5,float param6,float param7,/*MAV_CMD*/ushort command,byte target_system,byte target_component,byte confirmation) + public mavlink_hil_optical_flow_t(ulong time_usec,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,uint time_delta_distance_us,float distance,short temperature,byte sensor_id,byte quality) { - this.param1 = param1; - this.param2 = param2; - this.param3 = param3; - this.param4 = param4; - this.param5 = param5; - this.param6 = param6; - this.param7 = param7; - this.command = command; - this.target_system = target_system; - this.target_component = target_component; - this.confirmation = confirmation; + this.time_usec = time_usec; + this.integration_time_us = integration_time_us; + this.integrated_x = integrated_x; + this.integrated_y = integrated_y; + this.integrated_xgyro = integrated_xgyro; + this.integrated_ygyro = integrated_ygyro; + this.integrated_zgyro = integrated_zgyro; + this.time_delta_distance_us = time_delta_distance_us; + this.distance = distance; + this.temperature = temperature; + this.sensor_id = sensor_id; + this.quality = quality; } /// packet xml order - public static mavlink_command_long_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_CMD*/ushort command,byte confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) + public static mavlink_hil_optical_flow_t PopulateXMLOrder(ulong time_usec,byte sensor_id,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,short temperature,byte quality,uint time_delta_distance_us,float distance) { - var msg = new mavlink_command_long_t(); + var msg = new mavlink_hil_optical_flow_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.command = command; - msg.confirmation = confirmation; - msg.param1 = param1; - msg.param2 = param2; - msg.param3 = param3; - msg.param4 = param4; - msg.param5 = param5; - msg.param6 = param6; - msg.param7 = param7; + msg.time_usec = time_usec; + msg.sensor_id = sensor_id; + msg.integration_time_us = integration_time_us; + msg.integrated_x = integrated_x; + msg.integrated_y = integrated_y; + msg.integrated_xgyro = integrated_xgyro; + msg.integrated_ygyro = integrated_ygyro; + msg.integrated_zgyro = integrated_zgyro; + msg.temperature = temperature; + msg.quality = quality; + msg.time_delta_distance_us = time_delta_distance_us; + msg.distance = distance; return msg; } - /// Parameter 1 (for the specific command). - [Units("")] - [Description("Parameter 1 (for the specific command).")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public float param1; - - /// Parameter 2 (for the specific command). - [Units("")] - [Description("Parameter 2 (for the specific command).")] - //[FieldOffset(4)] - public float param2; + public ulong time_usec; - /// Parameter 3 (for the specific command). - [Units("")] - [Description("Parameter 3 (for the specific command).")] + /// Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. [us] + [Units("[us]")] + [Description("Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.")] //[FieldOffset(8)] - public float param3; + public uint integration_time_us; - /// Parameter 4 (for the specific command). - [Units("")] - [Description("Parameter 4 (for the specific command).")] + /// Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) [rad] + [Units("[rad]")] + [Description("Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)")] //[FieldOffset(12)] - public float param4; + public float integrated_x; - /// Parameter 5 (for the specific command). - [Units("")] - [Description("Parameter 5 (for the specific command).")] + /// Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) [rad] + [Units("[rad]")] + [Description("Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)")] //[FieldOffset(16)] - public float param5; + public float integrated_y; - /// Parameter 6 (for the specific command). - [Units("")] - [Description("Parameter 6 (for the specific command).")] + /// RH rotation around X axis [rad] + [Units("[rad]")] + [Description("RH rotation around X axis")] //[FieldOffset(20)] - public float param6; + public float integrated_xgyro; - /// Parameter 7 (for the specific command). - [Units("")] - [Description("Parameter 7 (for the specific command).")] + /// RH rotation around Y axis [rad] + [Units("[rad]")] + [Description("RH rotation around Y axis")] //[FieldOffset(24)] - public float param7; + public float integrated_ygyro; - /// Command ID (of command to send). MAV_CMD - [Units("")] - [Description("Command ID (of command to send).")] + /// RH rotation around Z axis [rad] + [Units("[rad]")] + [Description("RH rotation around Z axis")] //[FieldOffset(28)] - public /*MAV_CMD*/ushort command; + public float integrated_zgyro; - /// System which should execute the command - [Units("")] - [Description("System which should execute the command")] - //[FieldOffset(30)] - public byte target_system; + /// Time since the distance was sampled. [us] + [Units("[us]")] + [Description("Time since the distance was sampled.")] + //[FieldOffset(32)] + public uint time_delta_distance_us; - /// Component which should execute the command, 0 for all components + /// Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. [m] + [Units("[m]")] + [Description("Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.")] + //[FieldOffset(36)] + public float distance; + + /// Temperature [cdegC] + [Units("[cdegC]")] + [Description("Temperature")] + //[FieldOffset(40)] + public short temperature; + + /// Sensor ID [Units("")] - [Description("Component which should execute the command, 0 for all components")] - //[FieldOffset(31)] - public byte target_component; + [Description("Sensor ID")] + //[FieldOffset(42)] + public byte sensor_id; - /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + /// Optical flow quality / confidence. 0: no valid flow, 255: maximum quality [Units("")] - [Description("0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)")] - //[FieldOffset(32)] - public byte confirmation; + [Description("Optical flow quality / confidence. 0: no valid flow, 255: maximum quality")] + //[FieldOffset(43)] + public byte quality; }; - /// extensions_start 2 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=10)] - /// Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html - public struct mavlink_command_ack_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=64)] + /// Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. + public struct mavlink_hil_state_quaternion_t { /// packet ordered constructor - public mavlink_command_ack_t(/*MAV_CMD*/ushort command,/*MAV_RESULT*/byte result,byte progress,int result_param2,byte target_system,byte target_component) + public mavlink_hil_state_quaternion_t(ulong time_usec,float[] attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,ushort ind_airspeed,ushort true_airspeed,short xacc,short yacc,short zacc) { - this.command = command; - this.result = result; - this.progress = progress; - this.result_param2 = result_param2; - this.target_system = target_system; - this.target_component = target_component; + this.time_usec = time_usec; + this.attitude_quaternion = attitude_quaternion; + this.rollspeed = rollspeed; + this.pitchspeed = pitchspeed; + this.yawspeed = yawspeed; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.ind_airspeed = ind_airspeed; + this.true_airspeed = true_airspeed; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; } /// packet xml order - public static mavlink_command_ack_t PopulateXMLOrder(/*MAV_CMD*/ushort command,/*MAV_RESULT*/byte result,byte progress,int result_param2,byte target_system,byte target_component) + public static mavlink_hil_state_quaternion_t PopulateXMLOrder(ulong time_usec,float[] attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,ushort ind_airspeed,ushort true_airspeed,short xacc,short yacc,short zacc) { - var msg = new mavlink_command_ack_t(); + var msg = new mavlink_hil_state_quaternion_t(); - msg.command = command; - msg.result = result; - msg.progress = progress; - msg.result_param2 = result_param2; - msg.target_system = target_system; - msg.target_component = target_component; + msg.time_usec = time_usec; + msg.attitude_quaternion = attitude_quaternion; + msg.rollspeed = rollspeed; + msg.pitchspeed = pitchspeed; + msg.yawspeed = yawspeed; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.ind_airspeed = ind_airspeed; + msg.true_airspeed = true_airspeed; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; return msg; } - /// Command ID (of acknowledged command). MAV_CMD - [Units("")] - [Description("Command ID (of acknowledged command).")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public /*MAV_CMD*/ushort command; + public ulong time_usec; + + /// Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + [Units("")] + [Description("Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] attitude_quaternion; + + /// Body frame roll / phi angular speed [rad/s] + [Units("[rad/s]")] + [Description("Body frame roll / phi angular speed")] + //[FieldOffset(24)] + public float rollspeed; + + /// Body frame pitch / theta angular speed [rad/s] + [Units("[rad/s]")] + [Description("Body frame pitch / theta angular speed")] + //[FieldOffset(28)] + public float pitchspeed; + + /// Body frame yaw / psi angular speed [rad/s] + [Units("[rad/s]")] + [Description("Body frame yaw / psi angular speed")] + //[FieldOffset(32)] + public float yawspeed; + + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] + //[FieldOffset(36)] + public int lat; + + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] + //[FieldOffset(40)] + public int lon; + + /// Altitude [mm] + [Units("[mm]")] + [Description("Altitude")] + //[FieldOffset(44)] + public int alt; + + /// Ground X Speed (Latitude) [cm/s] + [Units("[cm/s]")] + [Description("Ground X Speed (Latitude)")] + //[FieldOffset(48)] + public short vx; + + /// Ground Y Speed (Longitude) [cm/s] + [Units("[cm/s]")] + [Description("Ground Y Speed (Longitude)")] + //[FieldOffset(50)] + public short vy; + + /// Ground Z Speed (Altitude) [cm/s] + [Units("[cm/s]")] + [Description("Ground Z Speed (Altitude)")] + //[FieldOffset(52)] + public short vz; - /// Result of command. MAV_RESULT - [Units("")] - [Description("Result of command.")] - //[FieldOffset(2)] - public /*MAV_RESULT*/byte result; + /// Indicated airspeed [cm/s] + [Units("[cm/s]")] + [Description("Indicated airspeed")] + //[FieldOffset(54)] + public ushort ind_airspeed; - /// Also used as result_param1, it can be set with a enum containing the errors reasons of why the command was denied or the progress percentage or 255 if unknown the progress when result is MAV_RESULT_IN_PROGRESS. - [Units("")] - [Description("Also used as result_param1, it can be set with a enum containing the errors reasons of why the command was denied or the progress percentage or 255 if unknown the progress when result is MAV_RESULT_IN_PROGRESS.")] - //[FieldOffset(3)] - public byte progress; + /// True airspeed [cm/s] + [Units("[cm/s]")] + [Description("True airspeed")] + //[FieldOffset(56)] + public ushort true_airspeed; - /// Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied. - [Units("")] - [Description("Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.")] - //[FieldOffset(4)] - public int result_param2; + /// X acceleration [mG] + [Units("[mG]")] + [Description("X acceleration")] + //[FieldOffset(58)] + public short xacc; - /// System which requested the command to be executed - [Units("")] - [Description("System which requested the command to be executed")] - //[FieldOffset(8)] - public byte target_system; + /// Y acceleration [mG] + [Units("[mG]")] + [Description("Y acceleration")] + //[FieldOffset(60)] + public short yacc; - /// Component which requested the command to be executed - [Units("")] - [Description("Component which requested the command to be executed")] - //[FieldOffset(9)] - public byte target_component; + /// Z acceleration [mG] + [Units("[mG]")] + [Description("Z acceleration")] + //[FieldOffset(62)] + public short zacc; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - /// Setpoint in roll, pitch, yaw and thrust from the operator - public struct mavlink_manual_setpoint_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units + public struct mavlink_scaled_imu2_t { /// packet ordered constructor - public mavlink_manual_setpoint_t(uint time_boot_ms,float roll,float pitch,float yaw,float thrust,byte mode_switch,byte manual_override_switch) + public mavlink_scaled_imu2_t(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) { this.time_boot_ms = time_boot_ms; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.thrust = thrust; - this.mode_switch = mode_switch; - this.manual_override_switch = manual_override_switch; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.xmag = xmag; + this.ymag = ymag; + this.zmag = zmag; + this.temperature = temperature; } /// packet xml order - public static mavlink_manual_setpoint_t PopulateXMLOrder(uint time_boot_ms,float roll,float pitch,float yaw,float thrust,byte mode_switch,byte manual_override_switch) + public static mavlink_scaled_imu2_t PopulateXMLOrder(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) { - var msg = new mavlink_manual_setpoint_t(); + var msg = new mavlink_scaled_imu2_t(); msg.time_boot_ms = time_boot_ms; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.thrust = thrust; - msg.mode_switch = mode_switch; - msg.manual_override_switch = manual_override_switch; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.xmag = xmag; + msg.ymag = ymag; + msg.zmag = zmag; + msg.temperature = temperature; return msg; } @@ -17089,1970 +22929,1657 @@ public static mavlink_manual_setpoint_t PopulateXMLOrder(uint time_boot_ms,float //[FieldOffset(0)] public uint time_boot_ms; - /// Desired roll rate [rad/s] - [Units("[rad/s]")] - [Description("Desired roll rate")] + /// X acceleration [mG] + [Units("[mG]")] + [Description("X acceleration")] //[FieldOffset(4)] - public float roll; + public short xacc; - /// Desired pitch rate [rad/s] - [Units("[rad/s]")] - [Description("Desired pitch rate")] + /// Y acceleration [mG] + [Units("[mG]")] + [Description("Y acceleration")] + //[FieldOffset(6)] + public short yacc; + + /// Z acceleration [mG] + [Units("[mG]")] + [Description("Z acceleration")] //[FieldOffset(8)] - public float pitch; + public short zacc; - /// Desired yaw rate [rad/s] - [Units("[rad/s]")] - [Description("Desired yaw rate")] + /// Angular speed around X axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around X axis")] + //[FieldOffset(10)] + public short xgyro; + + /// Angular speed around Y axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around Y axis")] //[FieldOffset(12)] - public float yaw; + public short ygyro; - /// Collective thrust, normalized to 0 .. 1 - [Units("")] - [Description("Collective thrust, normalized to 0 .. 1")] + /// Angular speed around Z axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around Z axis")] + //[FieldOffset(14)] + public short zgyro; + + /// X Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("X Magnetic field")] //[FieldOffset(16)] - public float thrust; + public short xmag; - /// Flight mode switch position, 0.. 255 - [Units("")] - [Description("Flight mode switch position, 0.. 255")] + /// Y Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("Y Magnetic field")] + //[FieldOffset(18)] + public short ymag; + + /// Z Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("Z Magnetic field")] //[FieldOffset(20)] - public byte mode_switch; + public short zmag; - /// Override mode switch position, 0.. 255 - [Units("")] - [Description("Override mode switch position, 0.. 255")] - //[FieldOffset(21)] - public byte manual_override_switch; + /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] + [Units("[cdegC]")] + [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] + //[FieldOffset(22)] + public short temperature; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=39)] - /// Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). - public struct mavlink_set_attitude_target_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0. + public struct mavlink_log_request_list_t { /// packet ordered constructor - public mavlink_set_attitude_target_t(uint time_boot_ms,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust,byte target_system,byte target_component,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask) + public mavlink_log_request_list_t(ushort start,ushort end,byte target_system,byte target_component) { - this.time_boot_ms = time_boot_ms; - this.q = q; - this.body_roll_rate = body_roll_rate; - this.body_pitch_rate = body_pitch_rate; - this.body_yaw_rate = body_yaw_rate; - this.thrust = thrust; + this.start = start; + this.end = end; this.target_system = target_system; this.target_component = target_component; - this.type_mask = type_mask; } /// packet xml order - public static mavlink_set_attitude_target_t PopulateXMLOrder(uint time_boot_ms,byte target_system,byte target_component,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) + public static mavlink_log_request_list_t PopulateXMLOrder(byte target_system,byte target_component,ushort start,ushort end) { - var msg = new mavlink_set_attitude_target_t(); + var msg = new mavlink_log_request_list_t(); - msg.time_boot_ms = time_boot_ms; msg.target_system = target_system; msg.target_component = target_component; - msg.type_mask = type_mask; - msg.q = q; - msg.body_roll_rate = body_roll_rate; - msg.body_pitch_rate = body_pitch_rate; - msg.body_yaw_rate = body_yaw_rate; - msg.thrust = thrust; + msg.start = start; + msg.end = end; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + /// First log id (0 for first available) [Units("")] - [Description("Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] - //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// Body roll rate [rad/s] - [Units("[rad/s]")] - [Description("Body roll rate")] - //[FieldOffset(20)] - public float body_roll_rate; - - /// Body pitch rate [rad/s] - [Units("[rad/s]")] - [Description("Body pitch rate")] - //[FieldOffset(24)] - public float body_pitch_rate; - - /// Body yaw rate [rad/s] - [Units("[rad/s]")] - [Description("Body yaw rate")] - //[FieldOffset(28)] - public float body_yaw_rate; + [Description("First log id (0 for first available)")] + //[FieldOffset(0)] + public ushort start; - /// Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + /// Last log id (0xffff for last available) [Units("")] - [Description("Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)")] - //[FieldOffset(32)] - public float thrust; + [Description("Last log id (0xffff for last available)")] + //[FieldOffset(2)] + public ushort end; /// System ID [Units("")] [Description("System ID")] - //[FieldOffset(36)] + //[FieldOffset(4)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(37)] + //[FieldOffset(5)] public byte target_component; - - /// Bitmap to indicate which dimensions should be ignored by the vehicle. ATTITUDE_TARGET_TYPEMASK bitmask - [Units("")] - [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] - //[FieldOffset(38)] - public /*ATTITUDE_TARGET_TYPEMASK*/byte type_mask; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - /// Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. - public struct mavlink_attitude_target_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// Reply to LOG_REQUEST_LIST + public struct mavlink_log_entry_t { /// packet ordered constructor - public mavlink_attitude_target_t(uint time_boot_ms,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask) + public mavlink_log_entry_t(uint time_utc,uint size,ushort id,ushort num_logs,ushort last_log_num) { - this.time_boot_ms = time_boot_ms; - this.q = q; - this.body_roll_rate = body_roll_rate; - this.body_pitch_rate = body_pitch_rate; - this.body_yaw_rate = body_yaw_rate; - this.thrust = thrust; - this.type_mask = type_mask; + this.time_utc = time_utc; + this.size = size; + this.id = id; + this.num_logs = num_logs; + this.last_log_num = last_log_num; } /// packet xml order - public static mavlink_attitude_target_t PopulateXMLOrder(uint time_boot_ms,/*ATTITUDE_TARGET_TYPEMASK*/byte type_mask,float[] q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) + public static mavlink_log_entry_t PopulateXMLOrder(ushort id,ushort num_logs,ushort last_log_num,uint time_utc,uint size) { - var msg = new mavlink_attitude_target_t(); + var msg = new mavlink_log_entry_t(); - msg.time_boot_ms = time_boot_ms; - msg.type_mask = type_mask; - msg.q = q; - msg.body_roll_rate = body_roll_rate; - msg.body_pitch_rate = body_pitch_rate; - msg.body_yaw_rate = body_yaw_rate; - msg.thrust = thrust; + msg.id = id; + msg.num_logs = num_logs; + msg.last_log_num = last_log_num; + msg.time_utc = time_utc; + msg.size = size; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// UTC timestamp of log since 1970, or 0 if not available [s] + [Units("[s]")] + [Description("UTC timestamp of log since 1970, or 0 if not available")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint time_utc; - /// Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - [Units("")] - [Description("Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] + /// Size of the log (may be approximate) [bytes] + [Units("[bytes]")] + [Description("Size of the log (may be approximate)")] //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// Body roll rate [rad/s] - [Units("[rad/s]")] - [Description("Body roll rate")] - //[FieldOffset(20)] - public float body_roll_rate; - - /// Body pitch rate [rad/s] - [Units("[rad/s]")] - [Description("Body pitch rate")] - //[FieldOffset(24)] - public float body_pitch_rate; + public uint size; - /// Body yaw rate [rad/s] - [Units("[rad/s]")] - [Description("Body yaw rate")] - //[FieldOffset(28)] - public float body_yaw_rate; + /// Log id + [Units("")] + [Description("Log id")] + //[FieldOffset(8)] + public ushort id; - /// Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + /// Total number of logs [Units("")] - [Description("Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)")] - //[FieldOffset(32)] - public float thrust; + [Description("Total number of logs")] + //[FieldOffset(10)] + public ushort num_logs; - /// Bitmap to indicate which dimensions should be ignored by the vehicle. ATTITUDE_TARGET_TYPEMASK bitmask + /// High log number [Units("")] - [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] - //[FieldOffset(36)] - public /*ATTITUDE_TARGET_TYPEMASK*/byte type_mask; + [Description("High log number")] + //[FieldOffset(12)] + public ushort last_log_num; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] - /// Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). - public struct mavlink_set_position_target_local_ned_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// Request a chunk of a log + public struct mavlink_log_request_data_t { /// packet ordered constructor - public mavlink_set_position_target_local_ned_t(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame) + public mavlink_log_request_data_t(uint ofs,uint count,ushort id,byte target_system,byte target_component) { - this.time_boot_ms = time_boot_ms; - this.x = x; - this.y = y; - this.z = z; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.afx = afx; - this.afy = afy; - this.afz = afz; - this.yaw = yaw; - this.yaw_rate = yaw_rate; - this.type_mask = type_mask; + this.ofs = ofs; + this.count = count; + this.id = id; this.target_system = target_system; this.target_component = target_component; - this.coordinate_frame = coordinate_frame; } /// packet xml order - public static mavlink_set_position_target_local_ned_t PopulateXMLOrder(uint time_boot_ms,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) + public static mavlink_log_request_data_t PopulateXMLOrder(byte target_system,byte target_component,ushort id,uint ofs,uint count) { - var msg = new mavlink_set_position_target_local_ned_t(); + var msg = new mavlink_log_request_data_t(); - msg.time_boot_ms = time_boot_ms; msg.target_system = target_system; msg.target_component = target_component; - msg.coordinate_frame = coordinate_frame; - msg.type_mask = type_mask; - msg.x = x; - msg.y = y; - msg.z = z; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.afx = afx; - msg.afy = afy; - msg.afz = afz; - msg.yaw = yaw; - msg.yaw_rate = yaw_rate; + msg.id = id; + msg.ofs = ofs; + msg.count = count; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Offset into the log + [Units("")] + [Description("Offset into the log")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint ofs; - /// X Position in NED frame [m] - [Units("[m]")] - [Description("X Position in NED frame")] + /// Number of bytes [bytes] + [Units("[bytes]")] + [Description("Number of bytes")] //[FieldOffset(4)] - public float x; + public uint count; - /// Y Position in NED frame [m] - [Units("[m]")] - [Description("Y Position in NED frame")] + /// Log id (from LOG_ENTRY reply) + [Units("")] + [Description("Log id (from LOG_ENTRY reply)")] //[FieldOffset(8)] - public float y; - - /// Z Position in NED frame (note, altitude is negative in NED) [m] - [Units("[m]")] - [Description("Z Position in NED frame (note, altitude is negative in NED)")] - //[FieldOffset(12)] - public float z; - - /// X velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("X velocity in NED frame")] - //[FieldOffset(16)] - public float vx; + public ushort id; - /// Y velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Y velocity in NED frame")] - //[FieldOffset(20)] - public float vy; + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(10)] + public byte target_system; - /// Z velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Z velocity in NED frame")] - //[FieldOffset(24)] - public float vz; + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(11)] + public byte target_component; + }; - /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(28)] - public float afx; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=97)] + /// Reply to LOG_REQUEST_DATA + public struct mavlink_log_data_t + { + /// packet ordered constructor + public mavlink_log_data_t(uint ofs,ushort id,byte count,byte[] data) + { + this.ofs = ofs; + this.id = id; + this.count = count; + this.data = data; + + } + + /// packet xml order + public static mavlink_log_data_t PopulateXMLOrder(ushort id,uint ofs,byte count,byte[] data) + { + var msg = new mavlink_log_data_t(); - /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(32)] - public float afy; + msg.id = id; + msg.ofs = ofs; + msg.count = count; + msg.data = data; + + return msg; + } + - /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(36)] - public float afz; + /// Offset into the log + [Units("")] + [Description("Offset into the log")] + //[FieldOffset(0)] + public uint ofs; - /// yaw setpoint [rad] - [Units("[rad]")] - [Description("yaw setpoint")] - //[FieldOffset(40)] - public float yaw; + /// Log id (from LOG_ENTRY reply) + [Units("")] + [Description("Log id (from LOG_ENTRY reply)")] + //[FieldOffset(4)] + public ushort id; - /// yaw rate setpoint [rad/s] - [Units("[rad/s]")] - [Description("yaw rate setpoint")] - //[FieldOffset(44)] - public float yaw_rate; + /// Number of bytes (zero for end of log) [bytes] + [Units("[bytes]")] + [Description("Number of bytes (zero for end of log)")] + //[FieldOffset(6)] + public byte count; - /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask + /// log data [Units("")] - [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] - //[FieldOffset(48)] - public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; + [Description("log data")] + //[FieldOffset(7)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=90)] + public byte[] data; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Erase all logs + public struct mavlink_log_erase_t + { + /// packet ordered constructor + public mavlink_log_erase_t(byte target_system,byte target_component) + { + this.target_system = target_system; + this.target_component = target_component; + + } + + /// packet xml order + public static mavlink_log_erase_t PopulateXMLOrder(byte target_system,byte target_component) + { + var msg = new mavlink_log_erase_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + + return msg; + } + /// System ID [Units("")] [Description("System ID")] - //[FieldOffset(50)] + //[FieldOffset(0)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(51)] + //[FieldOffset(1)] public byte target_component; - - /// Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 MAV_FRAME - [Units("")] - [Description("Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9")] - //[FieldOffset(52)] - public /*MAV_FRAME*/byte coordinate_frame; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] - /// Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. - public struct mavlink_position_target_local_ned_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Stop log transfer and resume normal logging + public struct mavlink_log_request_end_t { /// packet ordered constructor - public mavlink_position_target_local_ned_t(uint time_boot_ms,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,/*MAV_FRAME*/byte coordinate_frame) + public mavlink_log_request_end_t(byte target_system,byte target_component) { - this.time_boot_ms = time_boot_ms; - this.x = x; - this.y = y; - this.z = z; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.afx = afx; - this.afy = afy; - this.afz = afz; - this.yaw = yaw; - this.yaw_rate = yaw_rate; - this.type_mask = type_mask; - this.coordinate_frame = coordinate_frame; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_position_target_local_ned_t PopulateXMLOrder(uint time_boot_ms,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) + public static mavlink_log_request_end_t PopulateXMLOrder(byte target_system,byte target_component) { - var msg = new mavlink_position_target_local_ned_t(); + var msg = new mavlink_log_request_end_t(); - msg.time_boot_ms = time_boot_ms; - msg.coordinate_frame = coordinate_frame; - msg.type_mask = type_mask; - msg.x = x; - msg.y = y; - msg.z = z; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.afx = afx; - msg.afy = afy; - msg.afz = afz; - msg.yaw = yaw; - msg.yaw_rate = yaw_rate; + msg.target_system = target_system; + msg.target_component = target_component; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// X Position in NED frame [m] - [Units("[m]")] - [Description("X Position in NED frame")] - //[FieldOffset(4)] - public float x; - - /// Y Position in NED frame [m] - [Units("[m]")] - [Description("Y Position in NED frame")] - //[FieldOffset(8)] - public float y; - - /// Z Position in NED frame (note, altitude is negative in NED) [m] - [Units("[m]")] - [Description("Z Position in NED frame (note, altitude is negative in NED)")] - //[FieldOffset(12)] - public float z; - - /// X velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("X velocity in NED frame")] - //[FieldOffset(16)] - public float vx; - - /// Y velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Y velocity in NED frame")] - //[FieldOffset(20)] - public float vy; - - /// Z velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Z velocity in NED frame")] - //[FieldOffset(24)] - public float vz; - - /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(28)] - public float afx; - - /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(32)] - public float afy; - - /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(36)] - public float afz; - - /// yaw setpoint [rad] - [Units("[rad]")] - [Description("yaw setpoint")] - //[FieldOffset(40)] - public float yaw; - - /// yaw rate setpoint [rad/s] - [Units("[rad/s]")] - [Description("yaw rate setpoint")] - //[FieldOffset(44)] - public float yaw_rate; - - /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask + /// System ID [Units("")] - [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] - //[FieldOffset(48)] - public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; + [Description("System ID")] + //[FieldOffset(0)] + public byte target_system; - /// Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 MAV_FRAME + /// Component ID [Units("")] - [Description("Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9")] - //[FieldOffset(50)] - public /*MAV_FRAME*/byte coordinate_frame; + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] - /// Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). - public struct mavlink_set_position_target_global_int_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=113)] + /// Data for injecting into the onboard GPS (used for DGPS) + public struct mavlink_gps_inject_data_t { /// packet ordered constructor - public mavlink_set_position_target_global_int_t(uint time_boot_ms,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame) + public mavlink_gps_inject_data_t(byte target_system,byte target_component,byte len,byte[] data) { - this.time_boot_ms = time_boot_ms; - this.lat_int = lat_int; - this.lon_int = lon_int; - this.alt = alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.afx = afx; - this.afy = afy; - this.afz = afz; - this.yaw = yaw; - this.yaw_rate = yaw_rate; - this.type_mask = type_mask; this.target_system = target_system; this.target_component = target_component; - this.coordinate_frame = coordinate_frame; + this.len = len; + this.data = data; } /// packet xml order - public static mavlink_set_position_target_global_int_t PopulateXMLOrder(uint time_boot_ms,byte target_system,byte target_component,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) + public static mavlink_gps_inject_data_t PopulateXMLOrder(byte target_system,byte target_component,byte len,byte[] data) { - var msg = new mavlink_set_position_target_global_int_t(); + var msg = new mavlink_gps_inject_data_t(); - msg.time_boot_ms = time_boot_ms; msg.target_system = target_system; msg.target_component = target_component; - msg.coordinate_frame = coordinate_frame; - msg.type_mask = type_mask; - msg.lat_int = lat_int; - msg.lon_int = lon_int; - msg.alt = alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.afx = afx; - msg.afy = afy; - msg.afz = afz; - msg.yaw = yaw; - msg.yaw_rate = yaw_rate; + msg.len = len; + msg.data = data; return msg; } - /// Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// Latitude in WGS84 frame [degE7] - [Units("[degE7]")] - [Description("Latitude in WGS84 frame")] - //[FieldOffset(4)] - public int lat_int; - - /// Longitude in WGS84 frame [degE7] - [Units("[degE7]")] - [Description("Longitude in WGS84 frame")] - //[FieldOffset(8)] - public int lon_int; - - /// Altitude (MSL, Relative to home, or AGL - depending on frame) [m] - [Units("[m]")] - [Description("Altitude (MSL, Relative to home, or AGL - depending on frame)")] - //[FieldOffset(12)] - public float alt; - - /// X velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("X velocity in NED frame")] - //[FieldOffset(16)] - public float vx; - - /// Y velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Y velocity in NED frame")] - //[FieldOffset(20)] - public float vy; - - /// Z velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Z velocity in NED frame")] - //[FieldOffset(24)] - public float vz; - - /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(28)] - public float afx; - - /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(32)] - public float afy; - - /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(36)] - public float afz; - - /// yaw setpoint [rad] - [Units("[rad]")] - [Description("yaw setpoint")] - //[FieldOffset(40)] - public float yaw; - - /// yaw rate setpoint [rad/s] - [Units("[rad/s]")] - [Description("yaw rate setpoint")] - //[FieldOffset(44)] - public float yaw_rate; - - /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask - [Units("")] - [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] - //[FieldOffset(48)] - public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; - /// System ID [Units("")] [Description("System ID")] - //[FieldOffset(50)] + //[FieldOffset(0)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(51)] + //[FieldOffset(1)] public byte target_component; - /// Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated) MAV_FRAME + /// Data length [bytes] + [Units("[bytes]")] + [Description("Data length")] + //[FieldOffset(2)] + public byte len; + + /// Raw data (110 is enough for 12 satellites of RTCMv2) [Units("")] - [Description("Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)")] - //[FieldOffset(52)] - public /*MAV_FRAME*/byte coordinate_frame; + [Description("Raw data (110 is enough for 12 satellites of RTCMv2)")] + //[FieldOffset(3)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=110)] + public byte[] data; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] - /// Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. - public struct mavlink_position_target_global_int_t + /// extensions_start 12 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=57)] + /// Second GPS data. + public struct mavlink_gps2_raw_t { /// packet ordered constructor - public mavlink_position_target_global_int_t(uint time_boot_ms,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,/*MAV_FRAME*/byte coordinate_frame) + public mavlink_gps2_raw_t(ulong time_usec,int lat,int lon,int alt,uint dgps_age,ushort eph,ushort epv,ushort vel,ushort cog,/*GPS_FIX_TYPE*/byte fix_type,byte satellites_visible,byte dgps_numch,ushort yaw,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc) { - this.time_boot_ms = time_boot_ms; - this.lat_int = lat_int; - this.lon_int = lon_int; + this.time_usec = time_usec; + this.lat = lat; + this.lon = lon; this.alt = alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.afx = afx; - this.afy = afy; - this.afz = afz; + this.dgps_age = dgps_age; + this.eph = eph; + this.epv = epv; + this.vel = vel; + this.cog = cog; + this.fix_type = fix_type; + this.satellites_visible = satellites_visible; + this.dgps_numch = dgps_numch; this.yaw = yaw; - this.yaw_rate = yaw_rate; - this.type_mask = type_mask; - this.coordinate_frame = coordinate_frame; + this.alt_ellipsoid = alt_ellipsoid; + this.h_acc = h_acc; + this.v_acc = v_acc; + this.vel_acc = vel_acc; + this.hdg_acc = hdg_acc; } /// packet xml order - public static mavlink_position_target_global_int_t PopulateXMLOrder(uint time_boot_ms,/*MAV_FRAME*/byte coordinate_frame,/*POSITION_TARGET_TYPEMASK*/ushort type_mask,int lat_int,int lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) + public static mavlink_gps2_raw_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_TYPE*/byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,byte satellites_visible,byte dgps_numch,uint dgps_age,ushort yaw,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc) { - var msg = new mavlink_position_target_global_int_t(); + var msg = new mavlink_gps2_raw_t(); - msg.time_boot_ms = time_boot_ms; - msg.coordinate_frame = coordinate_frame; - msg.type_mask = type_mask; - msg.lat_int = lat_int; - msg.lon_int = lon_int; + msg.time_usec = time_usec; + msg.fix_type = fix_type; + msg.lat = lat; + msg.lon = lon; msg.alt = alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.afx = afx; - msg.afy = afy; - msg.afz = afz; + msg.eph = eph; + msg.epv = epv; + msg.vel = vel; + msg.cog = cog; + msg.satellites_visible = satellites_visible; + msg.dgps_numch = dgps_numch; + msg.dgps_age = dgps_age; msg.yaw = yaw; - msg.yaw_rate = yaw_rate; + msg.alt_ellipsoid = alt_ellipsoid; + msg.h_acc = h_acc; + msg.v_acc = v_acc; + msg.vel_acc = vel_acc; + msg.hdg_acc = hdg_acc; return msg; } - /// Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint time_boot_ms; - - /// Latitude in WGS84 frame [degE7] - [Units("[degE7]")] - [Description("Latitude in WGS84 frame")] - //[FieldOffset(4)] - public int lat_int; + public ulong time_usec; - /// Longitude in WGS84 frame [degE7] + /// Latitude (WGS84) [degE7] [Units("[degE7]")] - [Description("Longitude in WGS84 frame")] + [Description("Latitude (WGS84)")] //[FieldOffset(8)] - public int lon_int; + public int lat; - /// Altitude (MSL, AGL or relative to home altitude, depending on frame) [m] - [Units("[m]")] - [Description("Altitude (MSL, AGL or relative to home altitude, depending on frame)")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] //[FieldOffset(12)] - public float alt; + public int lon; - /// X velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("X velocity in NED frame")] + /// Altitude (MSL). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Positive for up.")] //[FieldOffset(16)] - public float vx; + public int alt; - /// Y velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Y velocity in NED frame")] + /// Age of DGPS info [ms] + [Units("[ms]")] + [Description("Age of DGPS info")] //[FieldOffset(20)] - public float vy; + public uint dgps_age; - /// Z velocity in NED frame [m/s] - [Units("[m/s]")] - [Description("Z velocity in NED frame")] + /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + [Units("")] + [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] //[FieldOffset(24)] - public float vz; + public ushort eph; - /// X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + [Units("")] + [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + //[FieldOffset(26)] + public ushort epv; + + /// GPS ground speed. If unknown, set to: UINT16_MAX [cm/s] + [Units("[cm/s]")] + [Description("GPS ground speed. If unknown, set to: UINT16_MAX")] //[FieldOffset(28)] - public float afx; + public ushort vel; - /// Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] + /// Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX [cdeg] + [Units("[cdeg]")] + [Description("Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX")] + //[FieldOffset(30)] + public ushort cog; + + /// GPS fix type. GPS_FIX_TYPE + [Units("")] + [Description("GPS fix type.")] //[FieldOffset(32)] - public float afy; + public /*GPS_FIX_TYPE*/byte fix_type; + + /// Number of satellites visible. If unknown, set to 255 + [Units("")] + [Description("Number of satellites visible. If unknown, set to 255")] + //[FieldOffset(33)] + public byte satellites_visible; + + /// Number of DGPS satellites + [Units("")] + [Description("Number of DGPS satellites")] + //[FieldOffset(34)] + public byte dgps_numch; + + /// Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. [cdeg] + [Units("[cdeg]")] + [Description("Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.")] + //[FieldOffset(35)] + public ushort yaw; + + /// Altitude (above WGS84, EGM96 ellipsoid). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (above WGS84, EGM96 ellipsoid). Positive for up.")] + //[FieldOffset(37)] + public int alt_ellipsoid; + + /// Position uncertainty. [mm] + [Units("[mm]")] + [Description("Position uncertainty.")] + //[FieldOffset(41)] + public uint h_acc; + + /// Altitude uncertainty. [mm] + [Units("[mm]")] + [Description("Altitude uncertainty.")] + //[FieldOffset(45)] + public uint v_acc; + + /// Speed uncertainty. [mm] + [Units("[mm]")] + [Description("Speed uncertainty.")] + //[FieldOffset(49)] + public uint vel_acc; - /// Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N")] - //[FieldOffset(36)] - public float afz; + /// Heading / track uncertainty [degE5] + [Units("[degE5]")] + [Description("Heading / track uncertainty")] + //[FieldOffset(53)] + public uint hdg_acc; + }; - /// yaw setpoint [rad] - [Units("[rad]")] - [Description("yaw setpoint")] - //[FieldOffset(40)] - public float yaw; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Power supply status + public struct mavlink_power_status_t + { + /// packet ordered constructor + public mavlink_power_status_t(ushort Vcc,ushort Vservo,/*MAV_POWER_STATUS*/ushort flags) + { + this.Vcc = Vcc; + this.Vservo = Vservo; + this.flags = flags; + + } + + /// packet xml order + public static mavlink_power_status_t PopulateXMLOrder(ushort Vcc,ushort Vservo,/*MAV_POWER_STATUS*/ushort flags) + { + var msg = new mavlink_power_status_t(); - /// yaw rate setpoint [rad/s] - [Units("[rad/s]")] - [Description("yaw rate setpoint")] - //[FieldOffset(44)] - public float yaw_rate; + msg.Vcc = Vcc; + msg.Vservo = Vservo; + msg.flags = flags; + + return msg; + } + - /// Bitmap to indicate which dimensions should be ignored by the vehicle. POSITION_TARGET_TYPEMASK bitmask - [Units("")] - [Description("Bitmap to indicate which dimensions should be ignored by the vehicle.")] - //[FieldOffset(48)] - public /*POSITION_TARGET_TYPEMASK*/ushort type_mask; + /// 5V rail voltage. [mV] + [Units("[mV]")] + [Description("5V rail voltage.")] + //[FieldOffset(0)] + public ushort Vcc; - /// Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated) MAV_FRAME + /// Servo rail voltage. [mV] + [Units("[mV]")] + [Description("Servo rail voltage.")] + //[FieldOffset(2)] + public ushort Vservo; + + /// Bitmap of power supply status flags. MAV_POWER_STATUS bitmask [Units("")] - [Description("Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)")] - //[FieldOffset(50)] - public /*MAV_FRAME*/byte coordinate_frame; + [Description("Bitmap of power supply status flags.")] + //[FieldOffset(4)] + public /*MAV_POWER_STATUS*/ushort flags; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - public struct mavlink_local_position_ned_system_global_offset_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=79)] + /// Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. + public struct mavlink_serial_control_t { /// packet ordered constructor - public mavlink_local_position_ned_system_global_offset_t(uint time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) + public mavlink_serial_control_t(uint baudrate,ushort timeout,/*SERIAL_CONTROL_DEV*/byte device,/*SERIAL_CONTROL_FLAG*/byte flags,byte count,byte[] data) { - this.time_boot_ms = time_boot_ms; - this.x = x; - this.y = y; - this.z = z; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; + this.baudrate = baudrate; + this.timeout = timeout; + this.device = device; + this.flags = flags; + this.count = count; + this.data = data; } /// packet xml order - public static mavlink_local_position_ned_system_global_offset_t PopulateXMLOrder(uint time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) + public static mavlink_serial_control_t PopulateXMLOrder(/*SERIAL_CONTROL_DEV*/byte device,/*SERIAL_CONTROL_FLAG*/byte flags,ushort timeout,uint baudrate,byte count,byte[] data) { - var msg = new mavlink_local_position_ned_system_global_offset_t(); + var msg = new mavlink_serial_control_t(); - msg.time_boot_ms = time_boot_ms; - msg.x = x; - msg.y = y; - msg.z = z; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; + msg.device = device; + msg.flags = flags; + msg.timeout = timeout; + msg.baudrate = baudrate; + msg.count = count; + msg.data = data; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Baudrate of transfer. Zero means no change. [bits/s] + [Units("[bits/s]")] + [Description("Baudrate of transfer. Zero means no change.")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint baudrate; - /// X Position [m] - [Units("[m]")] - [Description("X Position")] + /// Timeout for reply data [ms] + [Units("[ms]")] + [Description("Timeout for reply data")] //[FieldOffset(4)] - public float x; - - /// Y Position [m] - [Units("[m]")] - [Description("Y Position")] - //[FieldOffset(8)] - public float y; + public ushort timeout; - /// Z Position [m] - [Units("[m]")] - [Description("Z Position")] - //[FieldOffset(12)] - public float z; + /// Serial control device type. SERIAL_CONTROL_DEV + [Units("")] + [Description("Serial control device type.")] + //[FieldOffset(6)] + public /*SERIAL_CONTROL_DEV*/byte device; - /// Roll [rad] - [Units("[rad]")] - [Description("Roll")] - //[FieldOffset(16)] - public float roll; + /// Bitmap of serial control flags. SERIAL_CONTROL_FLAG bitmask + [Units("")] + [Description("Bitmap of serial control flags.")] + //[FieldOffset(7)] + public /*SERIAL_CONTROL_FLAG*/byte flags; - /// Pitch [rad] - [Units("[rad]")] - [Description("Pitch")] - //[FieldOffset(20)] - public float pitch; + /// how many bytes in this transfer [bytes] + [Units("[bytes]")] + [Description("how many bytes in this transfer")] + //[FieldOffset(8)] + public byte count; - /// Yaw [rad] - [Units("[rad]")] - [Description("Yaw")] - //[FieldOffset(24)] - public float yaw; + /// serial data + [Units("")] + [Description("serial data")] + //[FieldOffset(9)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=70)] + public byte[] data; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=56)] - /// Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. - public struct mavlink_hil_state_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] + /// RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + public struct mavlink_gps_rtk_t { /// packet ordered constructor - public mavlink_hil_state_t(ulong time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,short xacc,short yacc,short zacc) + public mavlink_gps_rtk_t(uint time_last_baseline_ms,uint tow,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses,ushort wn,byte rtk_receiver_id,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type) { - this.time_usec = time_usec; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.rollspeed = rollspeed; - this.pitchspeed = pitchspeed; - this.yawspeed = yawspeed; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; + this.time_last_baseline_ms = time_last_baseline_ms; + this.tow = tow; + this.baseline_a_mm = baseline_a_mm; + this.baseline_b_mm = baseline_b_mm; + this.baseline_c_mm = baseline_c_mm; + this.accuracy = accuracy; + this.iar_num_hypotheses = iar_num_hypotheses; + this.wn = wn; + this.rtk_receiver_id = rtk_receiver_id; + this.rtk_health = rtk_health; + this.rtk_rate = rtk_rate; + this.nsats = nsats; + this.baseline_coords_type = baseline_coords_type; } /// packet xml order - public static mavlink_hil_state_t PopulateXMLOrder(ulong time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,short xacc,short yacc,short zacc) + public static mavlink_gps_rtk_t PopulateXMLOrder(uint time_last_baseline_ms,byte rtk_receiver_id,ushort wn,uint tow,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses) { - var msg = new mavlink_hil_state_t(); + var msg = new mavlink_gps_rtk_t(); - msg.time_usec = time_usec; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.rollspeed = rollspeed; - msg.pitchspeed = pitchspeed; - msg.yawspeed = yawspeed; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; + msg.time_last_baseline_ms = time_last_baseline_ms; + msg.rtk_receiver_id = rtk_receiver_id; + msg.wn = wn; + msg.tow = tow; + msg.rtk_health = rtk_health; + msg.rtk_rate = rtk_rate; + msg.nsats = nsats; + msg.baseline_coords_type = baseline_coords_type; + msg.baseline_a_mm = baseline_a_mm; + msg.baseline_b_mm = baseline_b_mm; + msg.baseline_c_mm = baseline_c_mm; + msg.accuracy = accuracy; + msg.iar_num_hypotheses = iar_num_hypotheses; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Time since boot of last baseline message received. [ms] + [Units("[ms]")] + [Description("Time since boot of last baseline message received.")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_last_baseline_ms; - /// Roll angle [rad] - [Units("[rad]")] - [Description("Roll angle")] + /// GPS Time of Week of last baseline [ms] + [Units("[ms]")] + [Description("GPS Time of Week of last baseline")] + //[FieldOffset(4)] + public uint tow; + + /// Current baseline in ECEF x or NED north component. [mm] + [Units("[mm]")] + [Description("Current baseline in ECEF x or NED north component.")] //[FieldOffset(8)] - public float roll; + public int baseline_a_mm; - /// Pitch angle [rad] - [Units("[rad]")] - [Description("Pitch angle")] + /// Current baseline in ECEF y or NED east component. [mm] + [Units("[mm]")] + [Description("Current baseline in ECEF y or NED east component.")] //[FieldOffset(12)] - public float pitch; + public int baseline_b_mm; - /// Yaw angle [rad] - [Units("[rad]")] - [Description("Yaw angle")] + /// Current baseline in ECEF z or NED down component. [mm] + [Units("[mm]")] + [Description("Current baseline in ECEF z or NED down component.")] //[FieldOffset(16)] - public float yaw; + public int baseline_c_mm; - /// Body frame roll / phi angular speed [rad/s] - [Units("[rad/s]")] - [Description("Body frame roll / phi angular speed")] + /// Current estimate of baseline accuracy. + [Units("")] + [Description("Current estimate of baseline accuracy.")] //[FieldOffset(20)] - public float rollspeed; + public uint accuracy; - /// Body frame pitch / theta angular speed [rad/s] - [Units("[rad/s]")] - [Description("Body frame pitch / theta angular speed")] + /// Current number of integer ambiguity hypotheses. + [Units("")] + [Description("Current number of integer ambiguity hypotheses.")] //[FieldOffset(24)] - public float pitchspeed; + public int iar_num_hypotheses; - /// Body frame yaw / psi angular speed [rad/s] - [Units("[rad/s]")] - [Description("Body frame yaw / psi angular speed")] + /// GPS Week Number of last baseline + [Units("")] + [Description("GPS Week Number of last baseline")] //[FieldOffset(28)] - public float yawspeed; - - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] - //[FieldOffset(32)] - public int lat; - - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] - //[FieldOffset(36)] - public int lon; - - /// Altitude [mm] - [Units("[mm]")] - [Description("Altitude")] - //[FieldOffset(40)] - public int alt; - - /// Ground X Speed (Latitude) [cm/s] - [Units("[cm/s]")] - [Description("Ground X Speed (Latitude)")] - //[FieldOffset(44)] - public short vx; + public ushort wn; - /// Ground Y Speed (Longitude) [cm/s] - [Units("[cm/s]")] - [Description("Ground Y Speed (Longitude)")] - //[FieldOffset(46)] - public short vy; + /// Identification of connected RTK receiver. + [Units("")] + [Description("Identification of connected RTK receiver.")] + //[FieldOffset(30)] + public byte rtk_receiver_id; - /// Ground Z Speed (Altitude) [cm/s] - [Units("[cm/s]")] - [Description("Ground Z Speed (Altitude)")] - //[FieldOffset(48)] - public short vz; + /// GPS-specific health report for RTK data. + [Units("")] + [Description("GPS-specific health report for RTK data.")] + //[FieldOffset(31)] + public byte rtk_health; - /// X acceleration [mG] - [Units("[mG]")] - [Description("X acceleration")] - //[FieldOffset(50)] - public short xacc; + /// Rate of baseline messages being received by GPS [Hz] + [Units("[Hz]")] + [Description("Rate of baseline messages being received by GPS")] + //[FieldOffset(32)] + public byte rtk_rate; - /// Y acceleration [mG] - [Units("[mG]")] - [Description("Y acceleration")] - //[FieldOffset(52)] - public short yacc; + /// Current number of sats used for RTK calculation. + [Units("")] + [Description("Current number of sats used for RTK calculation.")] + //[FieldOffset(33)] + public byte nsats; - /// Z acceleration [mG] - [Units("[mG]")] - [Description("Z acceleration")] - //[FieldOffset(54)] - public short zacc; + /// Coordinate system of baseline RTK_BASELINE_COORDINATE_SYSTEM + [Units("")] + [Description("Coordinate system of baseline")] + //[FieldOffset(34)] + public /*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// Sent from autopilot to simulation. Hardware in the loop control outputs - public struct mavlink_hil_controls_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] + /// RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + public struct mavlink_gps2_rtk_t { /// packet ordered constructor - public mavlink_hil_controls_t(ulong time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,/*MAV_MODE*/byte mode,byte nav_mode) + public mavlink_gps2_rtk_t(uint time_last_baseline_ms,uint tow,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses,ushort wn,byte rtk_receiver_id,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type) { - this.time_usec = time_usec; - this.roll_ailerons = roll_ailerons; - this.pitch_elevator = pitch_elevator; - this.yaw_rudder = yaw_rudder; - this.throttle = throttle; - this.aux1 = aux1; - this.aux2 = aux2; - this.aux3 = aux3; - this.aux4 = aux4; - this.mode = mode; - this.nav_mode = nav_mode; + this.time_last_baseline_ms = time_last_baseline_ms; + this.tow = tow; + this.baseline_a_mm = baseline_a_mm; + this.baseline_b_mm = baseline_b_mm; + this.baseline_c_mm = baseline_c_mm; + this.accuracy = accuracy; + this.iar_num_hypotheses = iar_num_hypotheses; + this.wn = wn; + this.rtk_receiver_id = rtk_receiver_id; + this.rtk_health = rtk_health; + this.rtk_rate = rtk_rate; + this.nsats = nsats; + this.baseline_coords_type = baseline_coords_type; } /// packet xml order - public static mavlink_hil_controls_t PopulateXMLOrder(ulong time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,/*MAV_MODE*/byte mode,byte nav_mode) + public static mavlink_gps2_rtk_t PopulateXMLOrder(uint time_last_baseline_ms,byte rtk_receiver_id,ushort wn,uint tow,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses) { - var msg = new mavlink_hil_controls_t(); + var msg = new mavlink_gps2_rtk_t(); - msg.time_usec = time_usec; - msg.roll_ailerons = roll_ailerons; - msg.pitch_elevator = pitch_elevator; - msg.yaw_rudder = yaw_rudder; - msg.throttle = throttle; - msg.aux1 = aux1; - msg.aux2 = aux2; - msg.aux3 = aux3; - msg.aux4 = aux4; - msg.mode = mode; - msg.nav_mode = nav_mode; + msg.time_last_baseline_ms = time_last_baseline_ms; + msg.rtk_receiver_id = rtk_receiver_id; + msg.wn = wn; + msg.tow = tow; + msg.rtk_health = rtk_health; + msg.rtk_rate = rtk_rate; + msg.nsats = nsats; + msg.baseline_coords_type = baseline_coords_type; + msg.baseline_a_mm = baseline_a_mm; + msg.baseline_b_mm = baseline_b_mm; + msg.baseline_c_mm = baseline_c_mm; + msg.accuracy = accuracy; + msg.iar_num_hypotheses = iar_num_hypotheses; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Time since boot of last baseline message received. [ms] + [Units("[ms]")] + [Description("Time since boot of last baseline message received.")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_last_baseline_ms; - /// Control output -1 .. 1 - [Units("")] - [Description("Control output -1 .. 1")] + /// GPS Time of Week of last baseline [ms] + [Units("[ms]")] + [Description("GPS Time of Week of last baseline")] + //[FieldOffset(4)] + public uint tow; + + /// Current baseline in ECEF x or NED north component. [mm] + [Units("[mm]")] + [Description("Current baseline in ECEF x or NED north component.")] //[FieldOffset(8)] - public float roll_ailerons; + public int baseline_a_mm; - /// Control output -1 .. 1 - [Units("")] - [Description("Control output -1 .. 1")] + /// Current baseline in ECEF y or NED east component. [mm] + [Units("[mm]")] + [Description("Current baseline in ECEF y or NED east component.")] //[FieldOffset(12)] - public float pitch_elevator; + public int baseline_b_mm; - /// Control output -1 .. 1 - [Units("")] - [Description("Control output -1 .. 1")] + /// Current baseline in ECEF z or NED down component. [mm] + [Units("[mm]")] + [Description("Current baseline in ECEF z or NED down component.")] //[FieldOffset(16)] - public float yaw_rudder; + public int baseline_c_mm; - /// Throttle 0 .. 1 + /// Current estimate of baseline accuracy. [Units("")] - [Description("Throttle 0 .. 1")] + [Description("Current estimate of baseline accuracy.")] //[FieldOffset(20)] - public float throttle; + public uint accuracy; - /// Aux 1, -1 .. 1 + /// Current number of integer ambiguity hypotheses. [Units("")] - [Description("Aux 1, -1 .. 1")] + [Description("Current number of integer ambiguity hypotheses.")] //[FieldOffset(24)] - public float aux1; + public int iar_num_hypotheses; - /// Aux 2, -1 .. 1 + /// GPS Week Number of last baseline [Units("")] - [Description("Aux 2, -1 .. 1")] + [Description("GPS Week Number of last baseline")] //[FieldOffset(28)] - public float aux2; + public ushort wn; - /// Aux 3, -1 .. 1 + /// Identification of connected RTK receiver. [Units("")] - [Description("Aux 3, -1 .. 1")] - //[FieldOffset(32)] - public float aux3; + [Description("Identification of connected RTK receiver.")] + //[FieldOffset(30)] + public byte rtk_receiver_id; + + /// GPS-specific health report for RTK data. + [Units("")] + [Description("GPS-specific health report for RTK data.")] + //[FieldOffset(31)] + public byte rtk_health; - /// Aux 4, -1 .. 1 - [Units("")] - [Description("Aux 4, -1 .. 1")] - //[FieldOffset(36)] - public float aux4; + /// Rate of baseline messages being received by GPS [Hz] + [Units("[Hz]")] + [Description("Rate of baseline messages being received by GPS")] + //[FieldOffset(32)] + public byte rtk_rate; - /// System mode. MAV_MODE + /// Current number of sats used for RTK calculation. [Units("")] - [Description("System mode.")] - //[FieldOffset(40)] - public /*MAV_MODE*/byte mode; + [Description("Current number of sats used for RTK calculation.")] + //[FieldOffset(33)] + public byte nsats; - /// Navigation mode (MAV_NAV_MODE) + /// Coordinate system of baseline RTK_BASELINE_COORDINATE_SYSTEM [Units("")] - [Description("Navigation mode (MAV_NAV_MODE)")] - //[FieldOffset(41)] - public byte nav_mode; + [Description("Coordinate system of baseline")] + //[FieldOffset(34)] + public /*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] - /// Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - public struct mavlink_hil_rc_inputs_raw_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units + public struct mavlink_scaled_imu3_t { /// packet ordered constructor - public mavlink_hil_rc_inputs_raw_t(ulong time_usec,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,byte rssi) + public mavlink_scaled_imu3_t(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) { - this.time_usec = time_usec; - this.chan1_raw = chan1_raw; - this.chan2_raw = chan2_raw; - this.chan3_raw = chan3_raw; - this.chan4_raw = chan4_raw; - this.chan5_raw = chan5_raw; - this.chan6_raw = chan6_raw; - this.chan7_raw = chan7_raw; - this.chan8_raw = chan8_raw; - this.chan9_raw = chan9_raw; - this.chan10_raw = chan10_raw; - this.chan11_raw = chan11_raw; - this.chan12_raw = chan12_raw; - this.rssi = rssi; + this.time_boot_ms = time_boot_ms; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; + this.xmag = xmag; + this.ymag = ymag; + this.zmag = zmag; + this.temperature = temperature; } /// packet xml order - public static mavlink_hil_rc_inputs_raw_t PopulateXMLOrder(ulong time_usec,ushort chan1_raw,ushort chan2_raw,ushort chan3_raw,ushort chan4_raw,ushort chan5_raw,ushort chan6_raw,ushort chan7_raw,ushort chan8_raw,ushort chan9_raw,ushort chan10_raw,ushort chan11_raw,ushort chan12_raw,byte rssi) + public static mavlink_scaled_imu3_t PopulateXMLOrder(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) { - var msg = new mavlink_hil_rc_inputs_raw_t(); + var msg = new mavlink_scaled_imu3_t(); - msg.time_usec = time_usec; - msg.chan1_raw = chan1_raw; - msg.chan2_raw = chan2_raw; - msg.chan3_raw = chan3_raw; - msg.chan4_raw = chan4_raw; - msg.chan5_raw = chan5_raw; - msg.chan6_raw = chan6_raw; - msg.chan7_raw = chan7_raw; - msg.chan8_raw = chan8_raw; - msg.chan9_raw = chan9_raw; - msg.chan10_raw = chan10_raw; - msg.chan11_raw = chan11_raw; - msg.chan12_raw = chan12_raw; - msg.rssi = rssi; + msg.time_boot_ms = time_boot_ms; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; + msg.xmag = xmag; + msg.ymag = ymag; + msg.zmag = zmag; + msg.temperature = temperature; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// RC channel 1 value [us] - [Units("[us]")] - [Description("RC channel 1 value")] + /// X acceleration [mG] + [Units("[mG]")] + [Description("X acceleration")] + //[FieldOffset(4)] + public short xacc; + + /// Y acceleration [mG] + [Units("[mG]")] + [Description("Y acceleration")] + //[FieldOffset(6)] + public short yacc; + + /// Z acceleration [mG] + [Units("[mG]")] + [Description("Z acceleration")] //[FieldOffset(8)] - public ushort chan1_raw; + public short zacc; - /// RC channel 2 value [us] - [Units("[us]")] - [Description("RC channel 2 value")] + /// Angular speed around X axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around X axis")] //[FieldOffset(10)] - public ushort chan2_raw; + public short xgyro; - /// RC channel 3 value [us] - [Units("[us]")] - [Description("RC channel 3 value")] + /// Angular speed around Y axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around Y axis")] //[FieldOffset(12)] - public ushort chan3_raw; + public short ygyro; - /// RC channel 4 value [us] - [Units("[us]")] - [Description("RC channel 4 value")] + /// Angular speed around Z axis [mrad/s] + [Units("[mrad/s]")] + [Description("Angular speed around Z axis")] //[FieldOffset(14)] - public ushort chan4_raw; + public short zgyro; - /// RC channel 5 value [us] - [Units("[us]")] - [Description("RC channel 5 value")] + /// X Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("X Magnetic field")] //[FieldOffset(16)] - public ushort chan5_raw; + public short xmag; - /// RC channel 6 value [us] - [Units("[us]")] - [Description("RC channel 6 value")] + /// Y Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("Y Magnetic field")] //[FieldOffset(18)] - public ushort chan6_raw; + public short ymag; - /// RC channel 7 value [us] - [Units("[us]")] - [Description("RC channel 7 value")] + /// Z Magnetic field [mgauss] + [Units("[mgauss]")] + [Description("Z Magnetic field")] //[FieldOffset(20)] - public ushort chan7_raw; + public short zmag; - /// RC channel 8 value [us] - [Units("[us]")] - [Description("RC channel 8 value")] + /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] + [Units("[cdegC]")] + [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] //[FieldOffset(22)] - public ushort chan8_raw; + public short temperature; + }; - /// RC channel 9 value [us] - [Units("[us]")] - [Description("RC channel 9 value")] - //[FieldOffset(24)] - public ushort chan9_raw; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] + /// Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html. + public struct mavlink_data_transmission_handshake_t + { + /// packet ordered constructor + public mavlink_data_transmission_handshake_t(uint size,ushort width,ushort height,ushort packets,/*MAVLINK_DATA_STREAM_TYPE*/byte type,byte payload,byte jpg_quality) + { + this.size = size; + this.width = width; + this.height = height; + this.packets = packets; + this.type = type; + this.payload = payload; + this.jpg_quality = jpg_quality; + + } + + /// packet xml order + public static mavlink_data_transmission_handshake_t PopulateXMLOrder(/*MAVLINK_DATA_STREAM_TYPE*/byte type,uint size,ushort width,ushort height,ushort packets,byte payload,byte jpg_quality) + { + var msg = new mavlink_data_transmission_handshake_t(); - /// RC channel 10 value [us] - [Units("[us]")] - [Description("RC channel 10 value")] - //[FieldOffset(26)] - public ushort chan10_raw; + msg.type = type; + msg.size = size; + msg.width = width; + msg.height = height; + msg.packets = packets; + msg.payload = payload; + msg.jpg_quality = jpg_quality; + + return msg; + } + - /// RC channel 11 value [us] - [Units("[us]")] - [Description("RC channel 11 value")] - //[FieldOffset(28)] - public ushort chan11_raw; + /// total data size (set on ACK only). [bytes] + [Units("[bytes]")] + [Description("total data size (set on ACK only).")] + //[FieldOffset(0)] + public uint size; - /// RC channel 12 value [us] - [Units("[us]")] - [Description("RC channel 12 value")] - //[FieldOffset(30)] - public ushort chan12_raw; + /// Width of a matrix or image. + [Units("")] + [Description("Width of a matrix or image.")] + //[FieldOffset(4)] + public ushort width; - /// Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + /// Height of a matrix or image. [Units("")] - [Description("Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(32)] - public byte rssi; + [Description("Height of a matrix or image.")] + //[FieldOffset(6)] + public ushort height; + + /// Number of packets being sent (set on ACK only). + [Units("")] + [Description("Number of packets being sent (set on ACK only).")] + //[FieldOffset(8)] + public ushort packets; + + /// Type of requested/acknowledged data. MAVLINK_DATA_STREAM_TYPE + [Units("")] + [Description("Type of requested/acknowledged data.")] + //[FieldOffset(10)] + public /*MAVLINK_DATA_STREAM_TYPE*/byte type; + + /// Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). [bytes] + [Units("[bytes]")] + [Description("Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).")] + //[FieldOffset(11)] + public byte payload; + + /// JPEG quality. Values: [1-100]. [%] + [Units("[%]")] + [Description("JPEG quality. Values: [1-100].")] + //[FieldOffset(12)] + public byte jpg_quality; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=81)] - /// Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS) - public struct mavlink_hil_actuator_controls_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] + /// Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html. + public struct mavlink_encapsulated_data_t { /// packet ordered constructor - public mavlink_hil_actuator_controls_t(ulong time_usec,ulong flags,float[] controls,/*MAV_MODE_FLAG*/byte mode) + public mavlink_encapsulated_data_t(ushort seqnr,byte[] data) { - this.time_usec = time_usec; - this.flags = flags; - this.controls = controls; - this.mode = mode; + this.seqnr = seqnr; + this.data = data; } /// packet xml order - public static mavlink_hil_actuator_controls_t PopulateXMLOrder(ulong time_usec,float[] controls,/*MAV_MODE_FLAG*/byte mode,ulong flags) + public static mavlink_encapsulated_data_t PopulateXMLOrder(ushort seqnr,byte[] data) { - var msg = new mavlink_hil_actuator_controls_t(); + var msg = new mavlink_encapsulated_data_t(); - msg.time_usec = time_usec; - msg.controls = controls; - msg.mode = mode; - msg.flags = flags; + msg.seqnr = seqnr; + msg.data = data; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(0)] - public ulong time_usec; - - /// Flags as bitfield, 1: indicate simulation using lockstep. bitmask - [Units("")] - [Description("Flags as bitfield, 1: indicate simulation using lockstep.")] - //[FieldOffset(8)] - public ulong flags; - - /// Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. + /// sequence number (starting with 0 on every transmission) [Units("")] - [Description("Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public float[] controls; + [Description("sequence number (starting with 0 on every transmission)")] + //[FieldOffset(0)] + public ushort seqnr; - /// System mode. Includes arming state. MAV_MODE_FLAG bitmask + /// image data bytes [Units("")] - [Description("System mode. Includes arming state.")] - //[FieldOffset(80)] - public /*MAV_MODE_FLAG*/byte mode; + [Description("image data bytes")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=253)] + public byte[] data; }; /// extensions_start 8 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] - /// Optical flow from a flow sensor (e.g. optical mouse sensor) - public struct mavlink_optical_flow_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=39)] + /// Distance sensor information for an onboard rangefinder. + public struct mavlink_distance_sensor_t { /// packet ordered constructor - public mavlink_optical_flow_t(ulong time_usec,float flow_comp_m_x,float flow_comp_m_y,float ground_distance,short flow_x,short flow_y,byte sensor_id,byte quality,float flow_rate_x,float flow_rate_y) + public mavlink_distance_sensor_t(uint time_boot_ms,ushort min_distance,ushort max_distance,ushort current_distance,/*MAV_DISTANCE_SENSOR*/byte type,byte id,/*MAV_SENSOR_ORIENTATION*/byte orientation,byte covariance,float horizontal_fov,float vertical_fov,float[] quaternion,byte signal_quality) { - this.time_usec = time_usec; - this.flow_comp_m_x = flow_comp_m_x; - this.flow_comp_m_y = flow_comp_m_y; - this.ground_distance = ground_distance; - this.flow_x = flow_x; - this.flow_y = flow_y; - this.sensor_id = sensor_id; - this.quality = quality; - this.flow_rate_x = flow_rate_x; - this.flow_rate_y = flow_rate_y; + this.time_boot_ms = time_boot_ms; + this.min_distance = min_distance; + this.max_distance = max_distance; + this.current_distance = current_distance; + this.type = type; + this.id = id; + this.orientation = orientation; + this.covariance = covariance; + this.horizontal_fov = horizontal_fov; + this.vertical_fov = vertical_fov; + this.quaternion = quaternion; + this.signal_quality = signal_quality; } /// packet xml order - public static mavlink_optical_flow_t PopulateXMLOrder(ulong time_usec,byte sensor_id,short flow_x,short flow_y,float flow_comp_m_x,float flow_comp_m_y,byte quality,float ground_distance,float flow_rate_x,float flow_rate_y) + public static mavlink_distance_sensor_t PopulateXMLOrder(uint time_boot_ms,ushort min_distance,ushort max_distance,ushort current_distance,/*MAV_DISTANCE_SENSOR*/byte type,byte id,/*MAV_SENSOR_ORIENTATION*/byte orientation,byte covariance,float horizontal_fov,float vertical_fov,float[] quaternion,byte signal_quality) { - var msg = new mavlink_optical_flow_t(); + var msg = new mavlink_distance_sensor_t(); - msg.time_usec = time_usec; - msg.sensor_id = sensor_id; - msg.flow_x = flow_x; - msg.flow_y = flow_y; - msg.flow_comp_m_x = flow_comp_m_x; - msg.flow_comp_m_y = flow_comp_m_y; - msg.quality = quality; - msg.ground_distance = ground_distance; - msg.flow_rate_x = flow_rate_x; - msg.flow_rate_y = flow_rate_y; + msg.time_boot_ms = time_boot_ms; + msg.min_distance = min_distance; + msg.max_distance = max_distance; + msg.current_distance = current_distance; + msg.type = type; + msg.id = id; + msg.orientation = orientation; + msg.covariance = covariance; + msg.horizontal_fov = horizontal_fov; + msg.vertical_fov = vertical_fov; + msg.quaternion = quaternion; + msg.signal_quality = signal_quality; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; - - /// Flow in x-sensor direction, angular-speed compensated [m/s] - [Units("[m/s]")] - [Description("Flow in x-sensor direction, angular-speed compensated")] - //[FieldOffset(8)] - public float flow_comp_m_x; + public uint time_boot_ms; - /// Flow in y-sensor direction, angular-speed compensated [m/s] - [Units("[m/s]")] - [Description("Flow in y-sensor direction, angular-speed compensated")] - //[FieldOffset(12)] - public float flow_comp_m_y; + /// Minimum distance the sensor can measure [cm] + [Units("[cm]")] + [Description("Minimum distance the sensor can measure")] + //[FieldOffset(4)] + public ushort min_distance; - /// Ground distance. Positive value: distance known. Negative value: Unknown distance [m] - [Units("[m]")] - [Description("Ground distance. Positive value: distance known. Negative value: Unknown distance")] - //[FieldOffset(16)] - public float ground_distance; + /// Maximum distance the sensor can measure [cm] + [Units("[cm]")] + [Description("Maximum distance the sensor can measure")] + //[FieldOffset(6)] + public ushort max_distance; - /// 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; + /// Current distance reading [cm] + [Units("[cm]")] + [Description("Current distance reading")] + //[FieldOffset(8)] + public ushort current_distance; - /// 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; + /// Type of distance sensor. MAV_DISTANCE_SENSOR + [Units("")] + [Description("Type of distance sensor.")] + //[FieldOffset(10)] + public /*MAV_DISTANCE_SENSOR*/byte type; - /// Sensor ID + /// Onboard ID of the sensor [Units("")] - [Description("Sensor ID")] - //[FieldOffset(24)] - public byte sensor_id; + [Description("Onboard ID of the sensor")] + //[FieldOffset(11)] + public byte id; - /// Optical flow quality / confidence. 0: bad, 255: maximum quality + /// Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 MAV_SENSOR_ORIENTATION [Units("")] - [Description("Optical flow quality / confidence. 0: bad, 255: maximum quality")] - //[FieldOffset(25)] - public byte quality; + [Description("Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270")] + //[FieldOffset(12)] + public /*MAV_SENSOR_ORIENTATION*/byte orientation; - /// Flow rate about X axis [rad/s] - [Units("[rad/s]")] - [Description("Flow rate about X axis")] - //[FieldOffset(26)] - public float flow_rate_x; + /// Measurement variance. Max standard deviation is 6cm. 255 if unknown. [cm^2] + [Units("[cm^2]")] + [Description("Measurement variance. Max standard deviation is 6cm. 255 if unknown.")] + //[FieldOffset(13)] + public byte covariance; - /// Flow rate about Y axis [rad/s] - [Units("[rad/s]")] - [Description("Flow rate about Y axis")] - //[FieldOffset(30)] - public float flow_rate_y; + /// Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. [rad] + [Units("[rad]")] + [Description("Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.")] + //[FieldOffset(14)] + public float horizontal_fov; + + /// Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. [rad] + [Units("[rad]")] + [Description("Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.")] + //[FieldOffset(18)] + public float vertical_fov; + + /// Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.' + [Units("")] + [Description("Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.'")] + //[FieldOffset(22)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] quaternion; + + /// Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. [%] + [Units("[%]")] + [Description("Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.")] + //[FieldOffset(38)] + public byte signal_quality; }; - /// extensions_start 7 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=117)] - /// Global position/attitude estimate from a vision source. - public struct mavlink_global_vision_position_estimate_t - { - /// packet ordered constructor - public mavlink_global_vision_position_estimate_t(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) - { - this.usec = usec; - this.x = x; - this.y = y; - this.z = z; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.covariance = covariance; - this.reset_counter = reset_counter; + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] + /// Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html + public struct mavlink_terrain_request_t + { + /// packet ordered constructor + public mavlink_terrain_request_t(ulong mask,int lat,int lon,ushort grid_spacing) + { + this.mask = mask; + this.lat = lat; + this.lon = lon; + this.grid_spacing = grid_spacing; } /// packet xml order - public static mavlink_global_vision_position_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) + public static mavlink_terrain_request_t PopulateXMLOrder(int lat,int lon,ushort grid_spacing,ulong mask) { - var msg = new mavlink_global_vision_position_estimate_t(); + var msg = new mavlink_terrain_request_t(); - msg.usec = usec; - msg.x = x; - msg.y = y; - msg.z = z; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.covariance = covariance; - msg.reset_counter = reset_counter; + msg.lat = lat; + msg.lon = lon; + msg.grid_spacing = grid_spacing; + msg.mask = mask; return msg; } - /// Timestamp (UNIX time or since system boot) [us] - [Units("[us]")] - [Description("Timestamp (UNIX time or since system boot)")] + /// Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) bitmask + [Units("")] + [Description("Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)")] //[FieldOffset(0)] - public ulong usec; + public ulong mask; - /// Global X position [m] - [Units("[m]")] - [Description("Global X position")] + /// Latitude of SW corner of first grid [degE7] + [Units("[degE7]")] + [Description("Latitude of SW corner of first grid")] //[FieldOffset(8)] - public float x; + public int lat; - /// Global Y position [m] - [Units("[m]")] - [Description("Global Y position")] + /// Longitude of SW corner of first grid [degE7] + [Units("[degE7]")] + [Description("Longitude of SW corner of first grid")] //[FieldOffset(12)] - public float y; + public int lon; - /// Global Z position [m] + /// Grid spacing [m] [Units("[m]")] - [Description("Global Z position")] + [Description("Grid spacing")] //[FieldOffset(16)] - public float z; - - /// Roll angle [rad] - [Units("[rad]")] - [Description("Roll angle")] - //[FieldOffset(20)] - public float roll; - - /// Pitch angle [rad] - [Units("[rad]")] - [Description("Pitch angle")] - //[FieldOffset(24)] - public float pitch; - - /// Yaw angle [rad] - [Units("[rad]")] - [Description("Yaw angle")] - //[FieldOffset(28)] - public float yaw; - - /// Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - [Units("")] - [Description("Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] - public float[] covariance; - - /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - [Units("")] - [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] - //[FieldOffset(116)] - public byte reset_counter; + public ushort grid_spacing; }; - /// extensions_start 7 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=117)] - /// Local position/attitude estimate from a vision source. - public struct mavlink_vision_position_estimate_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=43)] + /// Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html + public struct mavlink_terrain_data_t { /// packet ordered constructor - public mavlink_vision_position_estimate_t(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) + public mavlink_terrain_data_t(int lat,int lon,ushort grid_spacing,short[] data,byte gridbit) { - this.usec = usec; - this.x = x; - this.y = y; - this.z = z; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.covariance = covariance; - this.reset_counter = reset_counter; + this.lat = lat; + this.lon = lon; + this.grid_spacing = grid_spacing; + this.data = data; + this.gridbit = gridbit; } /// packet xml order - public static mavlink_vision_position_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance,byte reset_counter) + public static mavlink_terrain_data_t PopulateXMLOrder(int lat,int lon,ushort grid_spacing,byte gridbit,short[] data) { - var msg = new mavlink_vision_position_estimate_t(); + var msg = new mavlink_terrain_data_t(); - msg.usec = usec; - msg.x = x; - msg.y = y; - msg.z = z; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.covariance = covariance; - msg.reset_counter = reset_counter; + msg.lat = lat; + msg.lon = lon; + msg.grid_spacing = grid_spacing; + msg.gridbit = gridbit; + msg.data = data; return msg; } - /// Timestamp (UNIX time or time since system boot) [us] - [Units("[us]")] - [Description("Timestamp (UNIX time or time since system boot)")] + /// Latitude of SW corner of first grid [degE7] + [Units("[degE7]")] + [Description("Latitude of SW corner of first grid")] //[FieldOffset(0)] - public ulong usec; + public int lat; - /// Local X position [m] - [Units("[m]")] - [Description("Local X position")] - //[FieldOffset(8)] - public float x; + /// Longitude of SW corner of first grid [degE7] + [Units("[degE7]")] + [Description("Longitude of SW corner of first grid")] + //[FieldOffset(4)] + public int lon; - /// Local Y position [m] + /// Grid spacing [m] [Units("[m]")] - [Description("Local Y position")] - //[FieldOffset(12)] - public float y; + [Description("Grid spacing")] + //[FieldOffset(8)] + public ushort grid_spacing; - /// Local Z position [m] + /// Terrain data MSL [m] [Units("[m]")] - [Description("Local Z position")] - //[FieldOffset(16)] - public float z; - - /// Roll angle [rad] - [Units("[rad]")] - [Description("Roll angle")] - //[FieldOffset(20)] - public float roll; - - /// Pitch angle [rad] - [Units("[rad]")] - [Description("Pitch angle")] - //[FieldOffset(24)] - public float pitch; - - /// Yaw angle [rad] - [Units("[rad]")] - [Description("Yaw angle")] - //[FieldOffset(28)] - public float yaw; - - /// Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - [Units("")] - [Description("Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] - public float[] covariance; + [Description("Terrain data MSL")] + //[FieldOffset(10)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public short[] data; - /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. + /// bit within the terrain request mask [Units("")] - [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] - //[FieldOffset(116)] - public byte reset_counter; + [Description("bit within the terrain request mask")] + //[FieldOffset(42)] + public byte gridbit; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=57)] - /// Speed estimate from a vision source. - public struct mavlink_vision_speed_estimate_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission. + public struct mavlink_terrain_check_t { /// packet ordered constructor - public mavlink_vision_speed_estimate_t(ulong usec,float x,float y,float z,float[] covariance,byte reset_counter) + public mavlink_terrain_check_t(int lat,int lon) { - this.usec = usec; - this.x = x; - this.y = y; - this.z = z; - this.covariance = covariance; - this.reset_counter = reset_counter; + this.lat = lat; + this.lon = lon; } /// packet xml order - public static mavlink_vision_speed_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float[] covariance,byte reset_counter) + public static mavlink_terrain_check_t PopulateXMLOrder(int lat,int lon) { - var msg = new mavlink_vision_speed_estimate_t(); + var msg = new mavlink_terrain_check_t(); - msg.usec = usec; - msg.x = x; - msg.y = y; - msg.z = z; - msg.covariance = covariance; - msg.reset_counter = reset_counter; + msg.lat = lat; + msg.lon = lon; return msg; } - /// Timestamp (UNIX time or time since system boot) [us] - [Units("[us]")] - [Description("Timestamp (UNIX time or time since system boot)")] + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] //[FieldOffset(0)] - public ulong usec; - - /// Global X speed [m/s] - [Units("[m/s]")] - [Description("Global X speed")] - //[FieldOffset(8)] - public float x; - - /// Global Y speed [m/s] - [Units("[m/s]")] - [Description("Global Y speed")] - //[FieldOffset(12)] - public float y; - - /// Global Z speed [m/s] - [Units("[m/s]")] - [Description("Global Z speed")] - //[FieldOffset(16)] - public float z; - - /// Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. - [Units("")] - [Description("Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] - public float[] covariance; + public int lat; - /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - [Units("")] - [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] - //[FieldOffset(56)] - public byte reset_counter; + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] + //[FieldOffset(4)] + public int lon; }; - /// extensions_start 7 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=116)] - /// Global position estimate from a Vicon motion system source. - public struct mavlink_vicon_position_estimate_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] + /// Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html + public struct mavlink_terrain_report_t { /// packet ordered constructor - public mavlink_vicon_position_estimate_t(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance) + public mavlink_terrain_report_t(int lat,int lon,float terrain_height,float current_height,ushort spacing,ushort pending,ushort loaded) { - this.usec = usec; - this.x = x; - this.y = y; - this.z = z; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.covariance = covariance; + this.lat = lat; + this.lon = lon; + this.terrain_height = terrain_height; + this.current_height = current_height; + this.spacing = spacing; + this.pending = pending; + this.loaded = loaded; } /// packet xml order - public static mavlink_vicon_position_estimate_t PopulateXMLOrder(ulong usec,float x,float y,float z,float roll,float pitch,float yaw,float[] covariance) + public static mavlink_terrain_report_t PopulateXMLOrder(int lat,int lon,ushort spacing,float terrain_height,float current_height,ushort pending,ushort loaded) { - var msg = new mavlink_vicon_position_estimate_t(); + var msg = new mavlink_terrain_report_t(); - msg.usec = usec; - msg.x = x; - msg.y = y; - msg.z = z; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.covariance = covariance; + msg.lat = lat; + msg.lon = lon; + msg.spacing = spacing; + msg.terrain_height = terrain_height; + msg.current_height = current_height; + msg.pending = pending; + msg.loaded = loaded; return msg; } - /// Timestamp (UNIX time or time since system boot) [us] - [Units("[us]")] - [Description("Timestamp (UNIX time or time since system boot)")] + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] //[FieldOffset(0)] - public ulong usec; + public int lat; - /// Global X position [m] + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] + //[FieldOffset(4)] + public int lon; + + /// Terrain height MSL [m] [Units("[m]")] - [Description("Global X position")] + [Description("Terrain height MSL")] //[FieldOffset(8)] - public float x; + public float terrain_height; - /// Global Y position [m] + /// Current vehicle height above lat/lon terrain height [m] [Units("[m]")] - [Description("Global Y position")] + [Description("Current vehicle height above lat/lon terrain height")] //[FieldOffset(12)] - public float y; + public float current_height; - /// Global Z position [m] - [Units("[m]")] - [Description("Global Z position")] + /// grid spacing (zero if terrain at this location unavailable) + [Units("")] + [Description("grid spacing (zero if terrain at this location unavailable)")] //[FieldOffset(16)] - public float z; - - /// Roll angle [rad] - [Units("[rad]")] - [Description("Roll angle")] - //[FieldOffset(20)] - public float roll; - - /// Pitch angle [rad] - [Units("[rad]")] - [Description("Pitch angle")] - //[FieldOffset(24)] - public float pitch; + public ushort spacing; - /// Yaw angle [rad] - [Units("[rad]")] - [Description("Yaw angle")] - //[FieldOffset(28)] - public float yaw; + /// Number of 4x4 terrain blocks waiting to be received or read from disk + [Units("")] + [Description("Number of 4x4 terrain blocks waiting to be received or read from disk")] + //[FieldOffset(18)] + public ushort pending; - /// Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. + /// Number of 4x4 terrain blocks in memory [Units("")] - [Description("Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] - public float[] covariance; + [Description("Number of 4x4 terrain blocks in memory")] + //[FieldOffset(20)] + public ushort loaded; }; - /// extensions_start 15 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=63)] - /// The IMU readings in SI units in NED body frame - public struct mavlink_highres_imu_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Barometer readings for 2nd barometer + public struct mavlink_scaled_pressure2_t { /// packet ordered constructor - public mavlink_highres_imu_t(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,ushort fields_updated,byte id) + public mavlink_scaled_pressure2_t(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) { - this.time_usec = time_usec; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.xmag = xmag; - this.ymag = ymag; - this.zmag = zmag; - this.abs_pressure = abs_pressure; - this.diff_pressure = diff_pressure; - this.pressure_alt = pressure_alt; + this.time_boot_ms = time_boot_ms; + this.press_abs = press_abs; + this.press_diff = press_diff; this.temperature = temperature; - this.fields_updated = fields_updated; - this.id = id; + this.temperature_press_diff = temperature_press_diff; } /// packet xml order - public static mavlink_highres_imu_t PopulateXMLOrder(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,ushort fields_updated,byte id) + public static mavlink_scaled_pressure2_t PopulateXMLOrder(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) { - var msg = new mavlink_highres_imu_t(); + var msg = new mavlink_scaled_pressure2_t(); - msg.time_usec = time_usec; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.xmag = xmag; - msg.ymag = ymag; - msg.zmag = zmag; - msg.abs_pressure = abs_pressure; - msg.diff_pressure = diff_pressure; - msg.pressure_alt = pressure_alt; + msg.time_boot_ms = time_boot_ms; + msg.press_abs = press_abs; + msg.press_diff = press_diff; msg.temperature = temperature; - msg.fields_updated = fields_updated; - msg.id = id; + msg.temperature_press_diff = temperature_press_diff; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; - - /// X acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration")] - //[FieldOffset(8)] - public float xacc; - - /// Y acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration")] - //[FieldOffset(12)] - public float yacc; - - /// Z acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration")] - //[FieldOffset(16)] - public float zacc; - - /// Angular speed around X axis [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around X axis")] - //[FieldOffset(20)] - public float xgyro; - - /// Angular speed around Y axis [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Y axis")] - //[FieldOffset(24)] - public float ygyro; - - /// Angular speed around Z axis [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Z axis")] - //[FieldOffset(28)] - public float zgyro; - - /// X Magnetic field [gauss] - [Units("[gauss]")] - [Description("X Magnetic field")] - //[FieldOffset(32)] - public float xmag; - - /// Y Magnetic field [gauss] - [Units("[gauss]")] - [Description("Y Magnetic field")] - //[FieldOffset(36)] - public float ymag; - - /// Z Magnetic field [gauss] - [Units("[gauss]")] - [Description("Z Magnetic field")] - //[FieldOffset(40)] - public float zmag; + public uint time_boot_ms; /// Absolute pressure [hPa] [Units("[hPa]")] [Description("Absolute pressure")] - //[FieldOffset(44)] - public float abs_pressure; + //[FieldOffset(4)] + public float press_abs; /// Differential pressure [hPa] - [Units("[hPa]")] - [Description("Differential pressure")] - //[FieldOffset(48)] - public float diff_pressure; - - /// Altitude calculated from pressure - [Units("")] - [Description("Altitude calculated from pressure")] - //[FieldOffset(52)] - public float pressure_alt; - - /// Temperature [degC] - [Units("[degC]")] - [Description("Temperature")] - //[FieldOffset(56)] - public float temperature; + [Units("[hPa]")] + [Description("Differential pressure")] + //[FieldOffset(8)] + public float press_diff; - /// Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature bitmask - [Units("")] - [Description("Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature")] - //[FieldOffset(60)] - public ushort fields_updated; + /// Absolute pressure temperature [cdegC] + [Units("[cdegC]")] + [Description("Absolute pressure temperature")] + //[FieldOffset(12)] + public short temperature; - /// Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - [Units("")] - [Description("Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)")] - //[FieldOffset(62)] - public byte id; + /// Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. [cdegC] + [Units("[cdegC]")] + [Description("Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.")] + //[FieldOffset(14)] + public short temperature_press_diff; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) - public struct mavlink_optical_flow_rad_t + /// extensions_start 5 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=120)] + /// Motion capture attitude and position + public struct mavlink_att_pos_mocap_t { /// packet ordered constructor - public mavlink_optical_flow_rad_t(ulong time_usec,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,uint time_delta_distance_us,float distance,short temperature,byte sensor_id,byte quality) + public mavlink_att_pos_mocap_t(ulong time_usec,float[] q,float x,float y,float z,float[] covariance) { this.time_usec = time_usec; - this.integration_time_us = integration_time_us; - this.integrated_x = integrated_x; - this.integrated_y = integrated_y; - this.integrated_xgyro = integrated_xgyro; - this.integrated_ygyro = integrated_ygyro; - this.integrated_zgyro = integrated_zgyro; - this.time_delta_distance_us = time_delta_distance_us; - this.distance = distance; - this.temperature = temperature; - this.sensor_id = sensor_id; - this.quality = quality; + this.q = q; + this.x = x; + this.y = y; + this.z = z; + this.covariance = covariance; } /// packet xml order - public static mavlink_optical_flow_rad_t PopulateXMLOrder(ulong time_usec,byte sensor_id,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,short temperature,byte quality,uint time_delta_distance_us,float distance) + public static mavlink_att_pos_mocap_t PopulateXMLOrder(ulong time_usec,float[] q,float x,float y,float z,float[] covariance) { - var msg = new mavlink_optical_flow_rad_t(); + var msg = new mavlink_att_pos_mocap_t(); msg.time_usec = time_usec; - msg.sensor_id = sensor_id; - msg.integration_time_us = integration_time_us; - msg.integrated_x = integrated_x; - msg.integrated_y = integrated_y; - msg.integrated_xgyro = integrated_xgyro; - msg.integrated_ygyro = integrated_ygyro; - msg.integrated_zgyro = integrated_zgyro; - msg.temperature = temperature; - msg.quality = quality; - msg.time_delta_distance_us = time_delta_distance_us; - msg.distance = distance; + msg.q = q; + msg.x = x; + msg.y = y; + msg.z = z; + msg.covariance = covariance; return msg; } @@ -19064,122 +24591,66 @@ public static mavlink_optical_flow_rad_t PopulateXMLOrder(ulong time_usec,byte s //[FieldOffset(0)] public ulong time_usec; - /// Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. [us] - [Units("[us]")] - [Description("Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.")] + /// Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + [Units("")] + [Description("Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] //[FieldOffset(8)] - public uint integration_time_us; - - /// Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) [rad] - [Units("[rad]")] - [Description("Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)")] - //[FieldOffset(12)] - public float integrated_x; - - /// Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) [rad] - [Units("[rad]")] - [Description("Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)")] - //[FieldOffset(16)] - public float integrated_y; - - /// RH rotation around X axis [rad] - [Units("[rad]")] - [Description("RH rotation around X axis")] - //[FieldOffset(20)] - public float integrated_xgyro; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// RH rotation around Y axis [rad] - [Units("[rad]")] - [Description("RH rotation around Y axis")] + /// X position (NED) [m] + [Units("[m]")] + [Description("X position (NED)")] //[FieldOffset(24)] - public float integrated_ygyro; + public float x; - /// RH rotation around Z axis [rad] - [Units("[rad]")] - [Description("RH rotation around Z axis")] + /// Y position (NED) [m] + [Units("[m]")] + [Description("Y position (NED)")] //[FieldOffset(28)] - public float integrated_zgyro; - - /// Time since the distance was sampled. [us] - [Units("[us]")] - [Description("Time since the distance was sampled.")] - //[FieldOffset(32)] - public uint time_delta_distance_us; + public float y; - /// Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. [m] + /// Z position (NED) [m] [Units("[m]")] - [Description("Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.")] - //[FieldOffset(36)] - public float distance; - - /// Temperature [cdegC] - [Units("[cdegC]")] - [Description("Temperature")] - //[FieldOffset(40)] - public short temperature; - - /// Sensor ID - [Units("")] - [Description("Sensor ID")] - //[FieldOffset(42)] - public byte sensor_id; + [Description("Z position (NED)")] + //[FieldOffset(32)] + public float z; - /// Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + /// Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("Optical flow quality / confidence. 0: no valid flow, 255: maximum quality")] - //[FieldOffset(43)] - public byte quality; + [Description("Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(36)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] + public float[] covariance; }; - /// extensions_start 15 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=65)] - /// The IMU readings in SI units in NED body frame - public struct mavlink_hil_sensor_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=43)] + /// Set the vehicle attitude and body angular rates. + public struct mavlink_set_actuator_control_target_t { /// packet ordered constructor - public mavlink_hil_sensor_t(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint fields_updated,byte id) + public mavlink_set_actuator_control_target_t(ulong time_usec,float[] controls,byte group_mlx,byte target_system,byte target_component) { this.time_usec = time_usec; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.xmag = xmag; - this.ymag = ymag; - this.zmag = zmag; - this.abs_pressure = abs_pressure; - this.diff_pressure = diff_pressure; - this.pressure_alt = pressure_alt; - this.temperature = temperature; - this.fields_updated = fields_updated; - this.id = id; + this.controls = controls; + this.group_mlx = group_mlx; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_hil_sensor_t PopulateXMLOrder(ulong time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint fields_updated,byte id) + public static mavlink_set_actuator_control_target_t PopulateXMLOrder(ulong time_usec,byte group_mlx,byte target_system,byte target_component,float[] controls) { - var msg = new mavlink_hil_sensor_t(); + var msg = new mavlink_set_actuator_control_target_t(); msg.time_usec = time_usec; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.xmag = xmag; - msg.ymag = ymag; - msg.zmag = zmag; - msg.abs_pressure = abs_pressure; - msg.diff_pressure = diff_pressure; - msg.pressure_alt = pressure_alt; - msg.temperature = temperature; - msg.fields_updated = fields_updated; - msg.id = id; + msg.group_mlx = group_mlx; + msg.target_system = target_system; + msg.target_component = target_component; + msg.controls = controls; return msg; } @@ -19191,828 +24662,870 @@ public static mavlink_hil_sensor_t PopulateXMLOrder(ulong time_usec,float xacc,f //[FieldOffset(0)] public ulong time_usec; - /// X acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration")] + /// Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + [Units("")] + [Description("Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.")] //[FieldOffset(8)] - public float xacc; - - /// Y acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration")] - //[FieldOffset(12)] - public float yacc; - - /// Z acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration")] - //[FieldOffset(16)] - public float zacc; - - /// Angular speed around X axis in body frame [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around X axis in body frame")] - //[FieldOffset(20)] - public float xgyro; - - /// Angular speed around Y axis in body frame [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Y axis in body frame")] - //[FieldOffset(24)] - public float ygyro; - - /// Angular speed around Z axis in body frame [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Z axis in body frame")] - //[FieldOffset(28)] - public float zgyro; - - /// X Magnetic field [gauss] - [Units("[gauss]")] - [Description("X Magnetic field")] - //[FieldOffset(32)] - public float xmag; - - /// Y Magnetic field [gauss] - [Units("[gauss]")] - [Description("Y Magnetic field")] - //[FieldOffset(36)] - public float ymag; - - /// Z Magnetic field [gauss] - [Units("[gauss]")] - [Description("Z Magnetic field")] - //[FieldOffset(40)] - public float zmag; - - /// Absolute pressure [hPa] - [Units("[hPa]")] - [Description("Absolute pressure")] - //[FieldOffset(44)] - public float abs_pressure; - - /// Differential pressure (airspeed) [hPa] - [Units("[hPa]")] - [Description("Differential pressure (airspeed)")] - //[FieldOffset(48)] - public float diff_pressure; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public float[] controls; - /// Altitude calculated from pressure + /// Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. [Units("")] - [Description("Altitude calculated from pressure")] - //[FieldOffset(52)] - public float pressure_alt; - - /// Temperature [degC] - [Units("[degC]")] - [Description("Temperature")] - //[FieldOffset(56)] - public float temperature; + [Description("Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.")] + //[FieldOffset(40)] + public byte group_mlx; - /// Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. bitmask + /// System ID [Units("")] - [Description("Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.")] - //[FieldOffset(60)] - public uint fields_updated; + [Description("System ID")] + //[FieldOffset(41)] + public byte target_system; - /// Sensor ID (zero indexed). Used for multiple sensor inputs + /// Component ID [Units("")] - [Description("Sensor ID (zero indexed). Used for multiple sensor inputs")] - //[FieldOffset(64)] - public byte id; + [Description("Component ID")] + //[FieldOffset(42)] + public byte target_component; }; - /// extensions_start 21 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=92)] - /// Status of simulation environment, if used - public struct mavlink_sim_state_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=41)] + /// Set the vehicle attitude and body angular rates. + public struct mavlink_actuator_control_target_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,int lat_int,int lon_int) + public mavlink_actuator_control_target_t(ulong time_usec,float[] controls,byte group_mlx) { - this.q1 = q1; - this.q2 = q2; - this.q3 = q3; - this.q4 = q4; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.std_dev_horz = std_dev_horz; - this.std_dev_vert = std_dev_vert; - this.vn = vn; - this.ve = ve; - this.vd = vd; - this.lat_int = lat_int; - this.lon_int = lon_int; + this.time_usec = time_usec; + this.controls = controls; + this.group_mlx = group_mlx; } /// 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,int lat_int,int lon_int) + public static mavlink_actuator_control_target_t PopulateXMLOrder(ulong time_usec,byte group_mlx,float[] controls) { - var msg = new mavlink_sim_state_t(); + var msg = new mavlink_actuator_control_target_t(); - msg.q1 = q1; - msg.q2 = q2; - msg.q3 = q3; - msg.q4 = q4; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.std_dev_horz = std_dev_horz; - msg.std_dev_vert = std_dev_vert; - msg.vn = vn; - msg.ve = ve; - msg.vd = vd; - msg.lat_int = lat_int; - msg.lon_int = lon_int; + msg.time_usec = time_usec; + msg.group_mlx = group_mlx; + msg.controls = controls; return msg; } - /// True attitude quaternion component 1, w (1 in null-rotation) - [Units("")] - [Description("True attitude quaternion component 1, w (1 in null-rotation)")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public float q1; - - /// True attitude quaternion component 2, x (0 in null-rotation) - [Units("")] - [Description("True attitude quaternion component 2, x (0 in null-rotation)")] - //[FieldOffset(4)] - public float q2; + public ulong time_usec; - /// True attitude quaternion component 3, y (0 in null-rotation) + /// Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. [Units("")] - [Description("True attitude quaternion component 3, y (0 in null-rotation)")] + [Description("Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.")] //[FieldOffset(8)] - public float q3; - - /// True attitude quaternion component 4, z (0 in null-rotation) - [Units("")] - [Description("True attitude quaternion component 4, z (0 in null-rotation)")] - //[FieldOffset(12)] - public float q4; - - /// Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - [Units("")] - [Description("Attitude roll expressed as Euler angles, not recommended except for human-readable outputs")] - //[FieldOffset(16)] - public float roll; - - /// Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - [Units("")] - [Description("Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs")] - //[FieldOffset(20)] - public float pitch; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public float[] controls; - /// Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + /// Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. [Units("")] - [Description("Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs")] - //[FieldOffset(24)] - public float yaw; - - /// X acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration")] - //[FieldOffset(28)] - public float xacc; - - /// Y acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration")] - //[FieldOffset(32)] - public float yacc; - - /// Z acceleration [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration")] - //[FieldOffset(36)] - public float zacc; - - /// Angular speed around X axis [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around X axis")] + [Description("Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.")] //[FieldOffset(40)] - public float xgyro; - - /// Angular speed around Y axis [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Y axis")] - //[FieldOffset(44)] - public float ygyro; + public byte group_mlx; + }; - /// Angular speed around Z axis [rad/s] - [Units("[rad/s]")] - [Description("Angular speed around Z axis")] - //[FieldOffset(48)] - public float zgyro; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] + /// The current system altitude. + public struct mavlink_altitude_t + { + /// packet ordered constructor + public mavlink_altitude_t(ulong time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) + { + this.time_usec = time_usec; + this.altitude_monotonic = altitude_monotonic; + this.altitude_amsl = altitude_amsl; + this.altitude_local = altitude_local; + this.altitude_relative = altitude_relative; + this.altitude_terrain = altitude_terrain; + this.bottom_clearance = bottom_clearance; + + } + + /// packet xml order + public static mavlink_altitude_t PopulateXMLOrder(ulong time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) + { + var msg = new mavlink_altitude_t(); - /// Latitude [deg] - [Units("[deg]")] - [Description("Latitude")] - //[FieldOffset(52)] - public float lat; + msg.time_usec = time_usec; + msg.altitude_monotonic = altitude_monotonic; + msg.altitude_amsl = altitude_amsl; + msg.altitude_local = altitude_local; + msg.altitude_relative = altitude_relative; + msg.altitude_terrain = altitude_terrain; + msg.bottom_clearance = bottom_clearance; + + return msg; + } + - /// Longitude [deg] - [Units("[deg]")] - [Description("Longitude")] - //[FieldOffset(56)] - public float lon; + /// 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. [us] + [Units("[us]")] + [Description("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.")] + //[FieldOffset(0)] + public ulong time_usec; - /// Altitude [m] + /// This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. [m] [Units("[m]")] - [Description("Altitude")] - //[FieldOffset(60)] - public float alt; - - /// Horizontal position standard deviation - [Units("")] - [Description("Horizontal position standard deviation")] - //[FieldOffset(64)] - public float std_dev_horz; - - /// Vertical position standard deviation - [Units("")] - [Description("Vertical position standard deviation")] - //[FieldOffset(68)] - public float std_dev_vert; + [Description("This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.")] + //[FieldOffset(8)] + public float altitude_monotonic; - /// True velocity in north direction in earth-fixed NED frame [m/s] - [Units("[m/s]")] - [Description("True velocity in north direction in earth-fixed NED frame")] - //[FieldOffset(72)] - public float vn; + /// This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. [m] + [Units("[m]")] + [Description("This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.")] + //[FieldOffset(12)] + public float altitude_amsl; - /// True velocity in east direction in earth-fixed NED frame [m/s] - [Units("[m/s]")] - [Description("True velocity in east direction in earth-fixed NED frame")] - //[FieldOffset(76)] - public float ve; + /// This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. [m] + [Units("[m]")] + [Description("This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.")] + //[FieldOffset(16)] + public float altitude_local; - /// True velocity in down direction in earth-fixed NED frame [m/s] - [Units("[m/s]")] - [Description("True velocity in down direction in earth-fixed NED frame")] - //[FieldOffset(80)] - public float vd; + /// This is the altitude above the home position. It resets on each change of the current home position. [m] + [Units("[m]")] + [Description("This is the altitude above the home position. It resets on each change of the current home position.")] + //[FieldOffset(20)] + public float altitude_relative; - /// 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; + /// This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. [m] + [Units("[m]")] + [Description("This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.")] + //[FieldOffset(24)] + public float altitude_terrain; - /// 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; + /// This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. [m] + [Units("[m]")] + [Description("This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.")] + //[FieldOffset(28)] + public float bottom_clearance; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Status generated by radio and injected into MAVLink stream. - public struct mavlink_radio_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=243)] + /// The autopilot is requesting a resource (file, binary, other type of data) + public struct mavlink_resource_request_t { /// packet ordered constructor - public mavlink_radio_status_t(ushort rxerrors,ushort @fixed,byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise) + public mavlink_resource_request_t(byte request_id,byte uri_type,byte[] uri,byte transfer_type,byte[] storage) { - this.rxerrors = rxerrors; - this.@fixed = @fixed; - this.rssi = rssi; - this.remrssi = remrssi; - this.txbuf = txbuf; - this.noise = noise; - this.remnoise = remnoise; + this.request_id = request_id; + this.uri_type = uri_type; + this.uri = uri; + this.transfer_type = transfer_type; + this.storage = storage; } /// packet xml order - public static mavlink_radio_status_t PopulateXMLOrder(byte rssi,byte remrssi,byte txbuf,byte noise,byte remnoise,ushort rxerrors,ushort @fixed) + public static mavlink_resource_request_t PopulateXMLOrder(byte request_id,byte uri_type,byte[] uri,byte transfer_type,byte[] storage) { - var msg = new mavlink_radio_status_t(); + var msg = new mavlink_resource_request_t(); - msg.rssi = rssi; - msg.remrssi = remrssi; - msg.txbuf = txbuf; - msg.noise = noise; - msg.remnoise = remnoise; - msg.rxerrors = rxerrors; - msg.@fixed = @fixed; + msg.request_id = request_id; + msg.uri_type = uri_type; + msg.uri = uri; + msg.transfer_type = transfer_type; + msg.storage = storage; return msg; } - /// Count of radio packet receive errors (since boot). + /// Request ID. This ID should be re-used when sending back URI contents [Units("")] - [Description("Count of radio packet receive errors (since boot).")] + [Description("Request ID. This ID should be re-used when sending back URI contents")] //[FieldOffset(0)] - public ushort rxerrors; - - /// Count of error corrected radio packets (since boot). - [Units("")] - [Description("Count of error corrected radio packets (since boot).")] - //[FieldOffset(2)] - public ushort @fixed; + public byte request_id; - /// Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + /// The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary [Units("")] - [Description("Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(4)] - public byte rssi; + [Description("The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary")] + //[FieldOffset(1)] + public byte uri_type; - /// Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown. + /// The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) [Units("")] - [Description("Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(5)] - public byte remrssi; - - /// Remaining free transmitter buffer space. [%] - [Units("[%]")] - [Description("Remaining free transmitter buffer space.")] - //[FieldOffset(6)] - public byte txbuf; + [Description("The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=120)] + public byte[] uri; - /// Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + /// The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. [Units("")] - [Description("Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(7)] - public byte noise; + [Description("The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.")] + //[FieldOffset(122)] + public byte transfer_type; - /// Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown. + /// The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). [Units("")] - [Description("Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.")] - //[FieldOffset(8)] - public byte remnoise; + [Description("The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).")] + //[FieldOffset(123)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=120)] + public byte[] storage; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=254)] - /// File transfer message - public struct mavlink_file_transfer_protocol_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Barometer readings for 3rd barometer + public struct mavlink_scaled_pressure3_t { /// packet ordered constructor - public mavlink_file_transfer_protocol_t(byte target_network,byte target_system,byte target_component,byte[] payload) + public mavlink_scaled_pressure3_t(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) { - this.target_network = target_network; - this.target_system = target_system; - this.target_component = target_component; - this.payload = payload; + this.time_boot_ms = time_boot_ms; + this.press_abs = press_abs; + this.press_diff = press_diff; + this.temperature = temperature; + this.temperature_press_diff = temperature_press_diff; } /// packet xml order - public static mavlink_file_transfer_protocol_t PopulateXMLOrder(byte target_network,byte target_system,byte target_component,byte[] payload) + public static mavlink_scaled_pressure3_t PopulateXMLOrder(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) { - var msg = new mavlink_file_transfer_protocol_t(); + var msg = new mavlink_scaled_pressure3_t(); - msg.target_network = target_network; - msg.target_system = target_system; - msg.target_component = target_component; - msg.payload = payload; + msg.time_boot_ms = time_boot_ms; + msg.press_abs = press_abs; + msg.press_diff = press_diff; + msg.temperature = temperature; + msg.temperature_press_diff = temperature_press_diff; return msg; } - /// Network ID (0 for broadcast) - [Units("")] - [Description("Network ID (0 for broadcast)")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public byte target_network; + public uint time_boot_ms; - /// System ID (0 for broadcast) - [Units("")] - [Description("System ID (0 for broadcast)")] - //[FieldOffset(1)] - public byte target_system; + /// Absolute pressure [hPa] + [Units("[hPa]")] + [Description("Absolute pressure")] + //[FieldOffset(4)] + public float press_abs; - /// Component ID (0 for broadcast) - [Units("")] - [Description("Component ID (0 for broadcast)")] - //[FieldOffset(2)] - public byte target_component; + /// Differential pressure [hPa] + [Units("[hPa]")] + [Description("Differential pressure")] + //[FieldOffset(8)] + public float press_diff; - /// Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - [Units("")] - [Description("Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.")] - //[FieldOffset(3)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=251)] - public byte[] payload; + /// Absolute pressure temperature [cdegC] + [Units("[cdegC]")] + [Description("Absolute pressure temperature")] + //[FieldOffset(12)] + public short temperature; + + /// Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. [cdegC] + [Units("[cdegC]")] + [Description("Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.")] + //[FieldOffset(14)] + public short temperature_press_diff; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// Time synchronization message. - public struct mavlink_timesync_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=93)] + /// Current motion information from a designated system + public struct mavlink_follow_target_t { /// packet ordered constructor - public mavlink_timesync_t(long tc1,long ts1) + public mavlink_follow_target_t(ulong timestamp,ulong custom_state,int lat,int lon,float alt,float[] vel,float[] acc,float[] attitude_q,float[] rates,float[] position_cov,byte est_capabilities) { - this.tc1 = tc1; - this.ts1 = ts1; + this.timestamp = timestamp; + this.custom_state = custom_state; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.vel = vel; + this.acc = acc; + this.attitude_q = attitude_q; + this.rates = rates; + this.position_cov = position_cov; + this.est_capabilities = est_capabilities; } /// packet xml order - public static mavlink_timesync_t PopulateXMLOrder(long tc1,long ts1) + public static mavlink_follow_target_t PopulateXMLOrder(ulong timestamp,byte est_capabilities,int lat,int lon,float alt,float[] vel,float[] acc,float[] attitude_q,float[] rates,float[] position_cov,ulong custom_state) { - var msg = new mavlink_timesync_t(); + var msg = new mavlink_follow_target_t(); - msg.tc1 = tc1; - msg.ts1 = ts1; + msg.timestamp = timestamp; + msg.est_capabilities = est_capabilities; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.vel = vel; + msg.acc = acc; + msg.attitude_q = attitude_q; + msg.rates = rates; + msg.position_cov = position_cov; + msg.custom_state = custom_state; return msg; } - /// Time sync timestamp 1 - [Units("")] - [Description("Time sync timestamp 1")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public long tc1; + public ulong timestamp; - /// Time sync timestamp 2 + /// button states or switches of a tracker device [Units("")] - [Description("Time sync timestamp 2")] + [Description("button states or switches of a tracker device")] //[FieldOffset(8)] - public long ts1; + public ulong custom_state; + + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] + //[FieldOffset(16)] + public int lat; + + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] + //[FieldOffset(20)] + public int lon; + + /// Altitude (MSL) [m] + [Units("[m]")] + [Description("Altitude (MSL)")] + //[FieldOffset(24)] + public float alt; + + /// target velocity (0,0,0) for unknown [m/s] + [Units("[m/s]")] + [Description("target velocity (0,0,0) for unknown")] + //[FieldOffset(28)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] vel; + + /// linear target acceleration (0,0,0) for unknown [m/s/s] + [Units("[m/s/s]")] + [Description("linear target acceleration (0,0,0) for unknown")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] acc; + + /// (1 0 0 0 for unknown) + [Units("")] + [Description("(1 0 0 0 for unknown)")] + //[FieldOffset(52)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] attitude_q; + + /// (0 0 0 for unknown) + [Units("")] + [Description("(0 0 0 for unknown)")] + //[FieldOffset(68)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] rates; + + /// eph epv + [Units("")] + [Description("eph epv")] + //[FieldOffset(80)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] position_cov; + + /// bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + [Units("")] + [Description("bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)")] + //[FieldOffset(92)] + public byte est_capabilities; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - /// Camera-IMU triggering and synchronisation message. - public struct mavlink_camera_trigger_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=100)] + /// The smoothed, monotonic system state used to feed the control loops of the system. + public struct mavlink_control_system_state_t { /// packet ordered constructor - public mavlink_camera_trigger_t(ulong time_usec,uint seq) + public mavlink_control_system_state_t(ulong time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,float[] vel_variance,float[] pos_variance,float[] q,float roll_rate,float pitch_rate,float yaw_rate) { this.time_usec = time_usec; - this.seq = seq; + this.x_acc = x_acc; + this.y_acc = y_acc; + this.z_acc = z_acc; + this.x_vel = x_vel; + this.y_vel = y_vel; + this.z_vel = z_vel; + this.x_pos = x_pos; + this.y_pos = y_pos; + this.z_pos = z_pos; + this.airspeed = airspeed; + this.vel_variance = vel_variance; + this.pos_variance = pos_variance; + this.q = q; + this.roll_rate = roll_rate; + this.pitch_rate = pitch_rate; + this.yaw_rate = yaw_rate; } /// packet xml order - public static mavlink_camera_trigger_t PopulateXMLOrder(ulong time_usec,uint seq) + public static mavlink_control_system_state_t PopulateXMLOrder(ulong time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,float[] vel_variance,float[] pos_variance,float[] q,float roll_rate,float pitch_rate,float yaw_rate) { - var msg = new mavlink_camera_trigger_t(); + var msg = new mavlink_control_system_state_t(); msg.time_usec = time_usec; - msg.seq = seq; + msg.x_acc = x_acc; + msg.y_acc = y_acc; + msg.z_acc = z_acc; + msg.x_vel = x_vel; + msg.y_vel = y_vel; + msg.z_vel = z_vel; + msg.x_pos = x_pos; + msg.y_pos = y_pos; + msg.z_pos = z_pos; + msg.airspeed = airspeed; + msg.vel_variance = vel_variance; + msg.pos_variance = pos_variance; + msg.q = q; + msg.roll_rate = roll_rate; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; return msg; } - /// Timestamp for image frame (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. [us] + /// 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. [us] [Units("[us]")] - [Description("Timestamp for image frame (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.")] + [Description("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.")] //[FieldOffset(0)] public ulong time_usec; - /// Image frame sequence - [Units("")] - [Description("Image frame sequence")] + /// X acceleration in body frame [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration in body frame")] //[FieldOffset(8)] - public uint seq; + public float x_acc; + + /// Y acceleration in body frame [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration in body frame")] + //[FieldOffset(12)] + public float y_acc; + + /// Z acceleration in body frame [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration in body frame")] + //[FieldOffset(16)] + public float z_acc; + + /// X velocity in body frame [m/s] + [Units("[m/s]")] + [Description("X velocity in body frame")] + //[FieldOffset(20)] + public float x_vel; + + /// Y velocity in body frame [m/s] + [Units("[m/s]")] + [Description("Y velocity in body frame")] + //[FieldOffset(24)] + public float y_vel; + + /// Z velocity in body frame [m/s] + [Units("[m/s]")] + [Description("Z velocity in body frame")] + //[FieldOffset(28)] + public float z_vel; + + /// X position in local frame [m] + [Units("[m]")] + [Description("X position in local frame")] + //[FieldOffset(32)] + public float x_pos; + + /// Y position in local frame [m] + [Units("[m]")] + [Description("Y position in local frame")] + //[FieldOffset(36)] + public float y_pos; + + /// Z position in local frame [m] + [Units("[m]")] + [Description("Z position in local frame")] + //[FieldOffset(40)] + public float z_pos; + + /// Airspeed, set to -1 if unknown [m/s] + [Units("[m/s]")] + [Description("Airspeed, set to -1 if unknown")] + //[FieldOffset(44)] + public float airspeed; + + /// Variance of body velocity estimate + [Units("")] + [Description("Variance of body velocity estimate")] + //[FieldOffset(48)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] vel_variance; + + /// Variance in local position + [Units("")] + [Description("Variance in local position")] + //[FieldOffset(60)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] pos_variance; + + /// The attitude, represented as Quaternion + [Units("")] + [Description("The attitude, represented as Quaternion")] + //[FieldOffset(72)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; + + /// Angular rate in roll axis [rad/s] + [Units("[rad/s]")] + [Description("Angular rate in roll axis")] + //[FieldOffset(88)] + public float roll_rate; + + /// Angular rate in pitch axis [rad/s] + [Units("[rad/s]")] + [Description("Angular rate in pitch axis")] + //[FieldOffset(92)] + public float pitch_rate; + + /// Angular rate in yaw axis [rad/s] + [Units("[rad/s]")] + [Description("Angular rate in yaw axis")] + //[FieldOffset(96)] + public float yaw_rate; }; - /// extensions_start 13 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=39)] - /// The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. - public struct mavlink_hil_gps_t + /// extensions_start 9 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] + /// Battery information + public struct mavlink_battery_status_t { /// packet ordered constructor - public mavlink_hil_gps_t(ulong time_usec,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,short vn,short ve,short vd,ushort cog,byte fix_type,byte satellites_visible,byte id,ushort yaw) + public mavlink_battery_status_t(int current_consumed,int energy_consumed,short temperature,ushort[] voltages,short current_battery,byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,sbyte battery_remaining,int time_remaining,/*MAV_BATTERY_CHARGE_STATE*/byte charge_state,ushort[] voltages_ext,/*MAV_BATTERY_MODE*/byte mode,/*MAV_BATTERY_FAULT*/uint fault_bitmask) { - this.time_usec = time_usec; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.eph = eph; - this.epv = epv; - this.vel = vel; - this.vn = vn; - this.ve = ve; - this.vd = vd; - this.cog = cog; - this.fix_type = fix_type; - this.satellites_visible = satellites_visible; + this.current_consumed = current_consumed; + this.energy_consumed = energy_consumed; + this.temperature = temperature; + this.voltages = voltages; + this.current_battery = current_battery; this.id = id; - this.yaw = yaw; + this.battery_function = battery_function; + this.type = type; + this.battery_remaining = battery_remaining; + this.time_remaining = time_remaining; + this.charge_state = charge_state; + this.voltages_ext = voltages_ext; + this.mode = mode; + this.fault_bitmask = fault_bitmask; } /// packet xml order - public static mavlink_hil_gps_t PopulateXMLOrder(ulong time_usec,byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,short vn,short ve,short vd,ushort cog,byte satellites_visible,byte id,ushort yaw) + public static mavlink_battery_status_t PopulateXMLOrder(byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,short temperature,ushort[] voltages,short current_battery,int current_consumed,int energy_consumed,sbyte battery_remaining,int time_remaining,/*MAV_BATTERY_CHARGE_STATE*/byte charge_state,ushort[] voltages_ext,/*MAV_BATTERY_MODE*/byte mode,/*MAV_BATTERY_FAULT*/uint fault_bitmask) { - var msg = new mavlink_hil_gps_t(); + var msg = new mavlink_battery_status_t(); - msg.time_usec = time_usec; - msg.fix_type = fix_type; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.eph = eph; - msg.epv = epv; - msg.vel = vel; - msg.vn = vn; - msg.ve = ve; - msg.vd = vd; - msg.cog = cog; - msg.satellites_visible = satellites_visible; msg.id = id; - msg.yaw = yaw; + msg.battery_function = battery_function; + msg.type = type; + msg.temperature = temperature; + msg.voltages = voltages; + msg.current_battery = current_battery; + msg.current_consumed = current_consumed; + msg.energy_consumed = energy_consumed; + msg.battery_remaining = battery_remaining; + msg.time_remaining = time_remaining; + msg.charge_state = charge_state; + msg.voltages_ext = voltages_ext; + msg.mode = mode; + msg.fault_bitmask = fault_bitmask; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Consumed charge, -1: autopilot does not provide consumption estimate [mAh] + [Units("[mAh]")] + [Description("Consumed charge, -1: autopilot does not provide consumption estimate")] //[FieldOffset(0)] - public ulong time_usec; + public int current_consumed; - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] + /// Consumed energy, -1: autopilot does not provide energy consumption estimate [hJ] + [Units("[hJ]")] + [Description("Consumed energy, -1: autopilot does not provide energy consumption estimate")] + //[FieldOffset(4)] + public int energy_consumed; + + /// Temperature of the battery. INT16_MAX for unknown temperature. [cdegC] + [Units("[cdegC]")] + [Description("Temperature of the battery. INT16_MAX for unknown temperature.")] //[FieldOffset(8)] - public int lat; + public short temperature; - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] - //[FieldOffset(12)] - public int lon; + /// Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). [mV] + [Units("[mV]")] + [Description("Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).")] + //[FieldOffset(10)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public ushort[] voltages; - /// Altitude (MSL). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up.")] - //[FieldOffset(16)] - public int alt; + /// Battery current, -1: autopilot does not measure the current [cA] + [Units("[cA]")] + [Description("Battery current, -1: autopilot does not measure the current")] + //[FieldOffset(30)] + public short current_battery; - /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + /// Battery ID [Units("")] - [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] - //[FieldOffset(20)] - public ushort eph; + [Description("Battery ID")] + //[FieldOffset(32)] + public byte id; - /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + /// Function of the battery MAV_BATTERY_FUNCTION [Units("")] - [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] - //[FieldOffset(22)] - public ushort epv; - - /// GPS ground speed. If unknown, set to: 65535 [cm/s] - [Units("[cm/s]")] - [Description("GPS ground speed. If unknown, set to: 65535")] - //[FieldOffset(24)] - public ushort vel; - - /// GPS velocity in north direction in earth-fixed NED frame [cm/s] - [Units("[cm/s]")] - [Description("GPS velocity in north direction in earth-fixed NED frame")] - //[FieldOffset(26)] - public short vn; + [Description("Function of the battery")] + //[FieldOffset(33)] + public /*MAV_BATTERY_FUNCTION*/byte battery_function; - /// GPS velocity in east direction in earth-fixed NED frame [cm/s] - [Units("[cm/s]")] - [Description("GPS velocity in east direction in earth-fixed NED frame")] - //[FieldOffset(28)] - public short ve; + /// Type (chemistry) of the battery MAV_BATTERY_TYPE + [Units("")] + [Description("Type (chemistry) of the battery")] + //[FieldOffset(34)] + public /*MAV_BATTERY_TYPE*/byte type; - /// GPS velocity in down direction in earth-fixed NED frame [cm/s] - [Units("[cm/s]")] - [Description("GPS velocity in down direction in earth-fixed NED frame")] - //[FieldOffset(30)] - public short vd; + /// Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. [%] + [Units("[%]")] + [Description("Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.")] + //[FieldOffset(35)] + public sbyte battery_remaining; - /// Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535 [cdeg] - [Units("[cdeg]")] - [Description("Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535")] - //[FieldOffset(32)] - public ushort cog; + /// Remaining battery time, 0: autopilot does not provide remaining battery time estimate [s] + [Units("[s]")] + [Description("Remaining battery time, 0: autopilot does not provide remaining battery time estimate")] + //[FieldOffset(36)] + public int time_remaining; - /// 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + /// State for extent of discharge, provided by autopilot for warning or external reactions MAV_BATTERY_CHARGE_STATE [Units("")] - [Description("0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.")] - //[FieldOffset(34)] - public byte fix_type; + [Description("State for extent of discharge, provided by autopilot for warning or external reactions")] + //[FieldOffset(40)] + public /*MAV_BATTERY_CHARGE_STATE*/byte charge_state; - /// Number of satellites visible. If unknown, set to 255 - [Units("")] - [Description("Number of satellites visible. If unknown, set to 255")] - //[FieldOffset(35)] - public byte satellites_visible; + /// Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. [mV] + [Units("[mV]")] + [Description("Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.")] + //[FieldOffset(41)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] voltages_ext; - /// GPS ID (zero indexed). Used for multiple GPS inputs + /// Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. MAV_BATTERY_MODE [Units("")] - [Description("GPS ID (zero indexed). Used for multiple GPS inputs")] - //[FieldOffset(36)] - public byte id; + [Description("Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.")] + //[FieldOffset(49)] + public /*MAV_BATTERY_MODE*/byte mode; - /// Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north [cdeg] - [Units("[cdeg]")] - [Description("Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north")] - //[FieldOffset(37)] - public ushort yaw; + /// Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). MAV_BATTERY_FAULT bitmask + [Units("")] + [Description("Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).")] + //[FieldOffset(50)] + public /*MAV_BATTERY_FAULT*/uint fault_bitmask; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) - public struct mavlink_hil_optical_flow_t + /// extensions_start 11 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=78)] + /// Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE. + public struct mavlink_autopilot_version_t { /// packet ordered constructor - public mavlink_hil_optical_flow_t(ulong time_usec,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,uint time_delta_distance_us,float distance,short temperature,byte sensor_id,byte quality) + public mavlink_autopilot_version_t(/*MAV_PROTOCOL_CAPABILITY*/ulong capabilities,ulong uid,uint flight_sw_version,uint middleware_sw_version,uint os_sw_version,uint board_version,ushort vendor_id,ushort product_id,byte[] flight_custom_version,byte[] middleware_custom_version,byte[] os_custom_version,byte[] uid2) { - this.time_usec = time_usec; - this.integration_time_us = integration_time_us; - this.integrated_x = integrated_x; - this.integrated_y = integrated_y; - this.integrated_xgyro = integrated_xgyro; - this.integrated_ygyro = integrated_ygyro; - this.integrated_zgyro = integrated_zgyro; - this.time_delta_distance_us = time_delta_distance_us; - this.distance = distance; - this.temperature = temperature; - this.sensor_id = sensor_id; - this.quality = quality; + this.capabilities = capabilities; + this.uid = uid; + this.flight_sw_version = flight_sw_version; + this.middleware_sw_version = middleware_sw_version; + this.os_sw_version = os_sw_version; + this.board_version = board_version; + this.vendor_id = vendor_id; + this.product_id = product_id; + this.flight_custom_version = flight_custom_version; + this.middleware_custom_version = middleware_custom_version; + this.os_custom_version = os_custom_version; + this.uid2 = uid2; } /// packet xml order - public static mavlink_hil_optical_flow_t PopulateXMLOrder(ulong time_usec,byte sensor_id,uint integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,short temperature,byte quality,uint time_delta_distance_us,float distance) + public static mavlink_autopilot_version_t PopulateXMLOrder(/*MAV_PROTOCOL_CAPABILITY*/ulong capabilities,uint flight_sw_version,uint middleware_sw_version,uint os_sw_version,uint board_version,byte[] flight_custom_version,byte[] middleware_custom_version,byte[] os_custom_version,ushort vendor_id,ushort product_id,ulong uid,byte[] uid2) { - var msg = new mavlink_hil_optical_flow_t(); + var msg = new mavlink_autopilot_version_t(); - msg.time_usec = time_usec; - msg.sensor_id = sensor_id; - msg.integration_time_us = integration_time_us; - msg.integrated_x = integrated_x; - msg.integrated_y = integrated_y; - msg.integrated_xgyro = integrated_xgyro; - msg.integrated_ygyro = integrated_ygyro; - msg.integrated_zgyro = integrated_zgyro; - msg.temperature = temperature; - msg.quality = quality; - msg.time_delta_distance_us = time_delta_distance_us; - msg.distance = distance; + msg.capabilities = capabilities; + msg.flight_sw_version = flight_sw_version; + msg.middleware_sw_version = middleware_sw_version; + msg.os_sw_version = os_sw_version; + msg.board_version = board_version; + msg.flight_custom_version = flight_custom_version; + msg.middleware_custom_version = middleware_custom_version; + msg.os_custom_version = os_custom_version; + msg.vendor_id = vendor_id; + msg.product_id = product_id; + msg.uid = uid; + msg.uid2 = uid2; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Bitmap of capabilities MAV_PROTOCOL_CAPABILITY bitmask + [Units("")] + [Description("Bitmap of capabilities")] //[FieldOffset(0)] - public ulong time_usec; + public /*MAV_PROTOCOL_CAPABILITY*/ulong capabilities; - /// Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. [us] - [Units("[us]")] - [Description("Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.")] + /// UID if provided by hardware (see uid2) + [Units("")] + [Description("UID if provided by hardware (see uid2)")] //[FieldOffset(8)] - public uint integration_time_us; - - /// Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) [rad] - [Units("[rad]")] - [Description("Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)")] - //[FieldOffset(12)] - public float integrated_x; + public ulong uid; - /// Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) [rad] - [Units("[rad]")] - [Description("Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)")] + /// Firmware version number + [Units("")] + [Description("Firmware version number")] //[FieldOffset(16)] - public float integrated_y; + public uint flight_sw_version; - /// RH rotation around X axis [rad] - [Units("[rad]")] - [Description("RH rotation around X axis")] + /// Middleware version number + [Units("")] + [Description("Middleware version number")] //[FieldOffset(20)] - public float integrated_xgyro; + public uint middleware_sw_version; - /// RH rotation around Y axis [rad] - [Units("[rad]")] - [Description("RH rotation around Y axis")] + /// Operating system version number + [Units("")] + [Description("Operating system version number")] //[FieldOffset(24)] - public float integrated_ygyro; + public uint os_sw_version; - /// RH rotation around Z axis [rad] - [Units("[rad]")] - [Description("RH rotation around Z axis")] + /// HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt + [Units("")] + [Description("HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt")] //[FieldOffset(28)] - public float integrated_zgyro; + public uint board_version; - /// Time since the distance was sampled. [us] - [Units("[us]")] - [Description("Time since the distance was sampled.")] + /// ID of the board vendor + [Units("")] + [Description("ID of the board vendor")] //[FieldOffset(32)] - public uint time_delta_distance_us; + public ushort vendor_id; - /// Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. [m] - [Units("[m]")] - [Description("Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.")] + /// ID of the product + [Units("")] + [Description("ID of the product")] + //[FieldOffset(34)] + public ushort product_id; + + /// Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + [Units("")] + [Description("Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.")] //[FieldOffset(36)] - public float distance; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] flight_custom_version; - /// Temperature [cdegC] - [Units("[cdegC]")] - [Description("Temperature")] - //[FieldOffset(40)] - public short temperature; + /// Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + [Units("")] + [Description("Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.")] + //[FieldOffset(44)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] middleware_custom_version; - /// Sensor ID + /// Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. [Units("")] - [Description("Sensor ID")] - //[FieldOffset(42)] - public byte sensor_id; + [Description("Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.")] + //[FieldOffset(52)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] os_custom_version; - /// Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + /// UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) [Units("")] - [Description("Optical flow quality / confidence. 0: no valid flow, 255: maximum quality")] - //[FieldOffset(43)] - public byte quality; + [Description("UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)")] + //[FieldOffset(60)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=18)] + public byte[] uid2; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=64)] - /// Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. - public struct mavlink_hil_state_quaternion_t + /// extensions_start 8 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=60)] + /// The location of a landing target. See: https://mavlink.io/en/services/landing_target.html + public struct mavlink_landing_target_t { /// packet ordered constructor - public mavlink_hil_state_quaternion_t(ulong time_usec,float[] attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,ushort ind_airspeed,ushort true_airspeed,short xacc,short yacc,short zacc) + public mavlink_landing_target_t(ulong time_usec,float angle_x,float angle_y,float distance,float size_x,float size_y,byte target_num,/*MAV_FRAME*/byte frame,float x,float y,float z,float[] q,/*LANDING_TARGET_TYPE*/byte type,byte position_valid) { this.time_usec = time_usec; - this.attitude_quaternion = attitude_quaternion; - this.rollspeed = rollspeed; - this.pitchspeed = pitchspeed; - this.yawspeed = yawspeed; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.ind_airspeed = ind_airspeed; - this.true_airspeed = true_airspeed; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; + this.angle_x = angle_x; + this.angle_y = angle_y; + this.distance = distance; + this.size_x = size_x; + this.size_y = size_y; + this.target_num = target_num; + this.frame = frame; + this.x = x; + this.y = y; + this.z = z; + this.q = q; + this.type = type; + this.position_valid = position_valid; } /// packet xml order - public static mavlink_hil_state_quaternion_t PopulateXMLOrder(ulong time_usec,float[] attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int lat,int lon,int alt,short vx,short vy,short vz,ushort ind_airspeed,ushort true_airspeed,short xacc,short yacc,short zacc) + public static mavlink_landing_target_t PopulateXMLOrder(ulong time_usec,byte target_num,/*MAV_FRAME*/byte frame,float angle_x,float angle_y,float distance,float size_x,float size_y,float x,float y,float z,float[] q,/*LANDING_TARGET_TYPE*/byte type,byte position_valid) { - var msg = new mavlink_hil_state_quaternion_t(); + var msg = new mavlink_landing_target_t(); msg.time_usec = time_usec; - msg.attitude_quaternion = attitude_quaternion; - msg.rollspeed = rollspeed; - msg.pitchspeed = pitchspeed; - msg.yawspeed = yawspeed; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.ind_airspeed = ind_airspeed; - msg.true_airspeed = true_airspeed; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; + msg.target_num = target_num; + msg.frame = frame; + msg.angle_x = angle_x; + msg.angle_y = angle_y; + msg.distance = distance; + msg.size_x = size_x; + msg.size_y = size_y; + msg.x = x; + msg.y = y; + msg.z = z; + msg.q = q; + msg.type = type; + msg.position_valid = position_valid; return msg; } @@ -20024,547 +25537,885 @@ public static mavlink_hil_state_quaternion_t PopulateXMLOrder(ulong time_usec,fl //[FieldOffset(0)] public ulong time_usec; - /// Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - [Units("")] - [Description("Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)")] + /// X-axis angular offset of the target from the center of the image [rad] + [Units("[rad]")] + [Description("X-axis angular offset of the target from the center of the image")] //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] attitude_quaternion; - - /// Body frame roll / phi angular speed [rad/s] - [Units("[rad/s]")] - [Description("Body frame roll / phi angular speed")] - //[FieldOffset(24)] - public float rollspeed; + public float angle_x; - /// Body frame pitch / theta angular speed [rad/s] - [Units("[rad/s]")] - [Description("Body frame pitch / theta angular speed")] - //[FieldOffset(28)] - public float pitchspeed; + /// Y-axis angular offset of the target from the center of the image [rad] + [Units("[rad]")] + [Description("Y-axis angular offset of the target from the center of the image")] + //[FieldOffset(12)] + public float angle_y; - /// Body frame yaw / psi angular speed [rad/s] - [Units("[rad/s]")] - [Description("Body frame yaw / psi angular speed")] - //[FieldOffset(32)] - public float yawspeed; + /// Distance to the target from the vehicle [m] + [Units("[m]")] + [Description("Distance to the target from the vehicle")] + //[FieldOffset(16)] + public float distance; - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] - //[FieldOffset(36)] - public int lat; + /// Size of target along x-axis [rad] + [Units("[rad]")] + [Description("Size of target along x-axis")] + //[FieldOffset(20)] + public float size_x; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] - //[FieldOffset(40)] - public int lon; + /// Size of target along y-axis [rad] + [Units("[rad]")] + [Description("Size of target along y-axis")] + //[FieldOffset(24)] + public float size_y; - /// Altitude [mm] - [Units("[mm]")] - [Description("Altitude")] - //[FieldOffset(44)] - public int alt; + /// The ID of the target if multiple targets are present + [Units("")] + [Description("The ID of the target if multiple targets are present")] + //[FieldOffset(28)] + public byte target_num; - /// Ground X Speed (Latitude) [cm/s] - [Units("[cm/s]")] - [Description("Ground X Speed (Latitude)")] - //[FieldOffset(48)] - public short vx; + /// Coordinate frame used for following fields. MAV_FRAME + [Units("")] + [Description("Coordinate frame used for following fields.")] + //[FieldOffset(29)] + public /*MAV_FRAME*/byte frame; - /// Ground Y Speed (Longitude) [cm/s] - [Units("[cm/s]")] - [Description("Ground Y Speed (Longitude)")] - //[FieldOffset(50)] - public short vy; + /// X Position of the landing target in MAV_FRAME [m] + [Units("[m]")] + [Description("X Position of the landing target in MAV_FRAME")] + //[FieldOffset(30)] + public float x; - /// Ground Z Speed (Altitude) [cm/s] - [Units("[cm/s]")] - [Description("Ground Z Speed (Altitude)")] - //[FieldOffset(52)] - public short vz; + /// Y Position of the landing target in MAV_FRAME [m] + [Units("[m]")] + [Description("Y Position of the landing target in MAV_FRAME")] + //[FieldOffset(34)] + public float y; - /// Indicated airspeed [cm/s] - [Units("[cm/s]")] - [Description("Indicated airspeed")] - //[FieldOffset(54)] - public ushort ind_airspeed; + /// Z Position of the landing target in MAV_FRAME [m] + [Units("[m]")] + [Description("Z Position of the landing target in MAV_FRAME")] + //[FieldOffset(38)] + public float z; - /// True airspeed [cm/s] - [Units("[cm/s]")] - [Description("True airspeed")] - //[FieldOffset(56)] - public ushort true_airspeed; + /// Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + [Units("")] + [Description("Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] + //[FieldOffset(42)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// X acceleration [mG] - [Units("[mG]")] - [Description("X acceleration")] + /// Type of landing target LANDING_TARGET_TYPE + [Units("")] + [Description("Type of landing target")] //[FieldOffset(58)] - public short xacc; - - /// Y acceleration [mG] - [Units("[mG]")] - [Description("Y acceleration")] - //[FieldOffset(60)] - public short yacc; + public /*LANDING_TARGET_TYPE*/byte type; - /// Z acceleration [mG] - [Units("[mG]")] - [Description("Z acceleration")] - //[FieldOffset(62)] - public short zacc; + /// Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). + [Units("")] + [Description("Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).")] + //[FieldOffset(59)] + public byte position_valid; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] - /// The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units - public struct mavlink_scaled_imu2_t + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Status of geo-fencing. Sent in extended status stream when fencing enabled. + public struct mavlink_fence_status_t { /// packet ordered constructor - public mavlink_scaled_imu2_t(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) + public mavlink_fence_status_t(uint breach_time,ushort breach_count,byte breach_status,/*FENCE_BREACH*/byte breach_type,/*FENCE_MITIGATE*/byte breach_mitigation) { - this.time_boot_ms = time_boot_ms; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.xmag = xmag; - this.ymag = ymag; - this.zmag = zmag; - this.temperature = temperature; + this.breach_time = breach_time; + this.breach_count = breach_count; + this.breach_status = breach_status; + this.breach_type = breach_type; + this.breach_mitigation = breach_mitigation; } /// packet xml order - public static mavlink_scaled_imu2_t PopulateXMLOrder(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) + public static mavlink_fence_status_t PopulateXMLOrder(byte breach_status,ushort breach_count,/*FENCE_BREACH*/byte breach_type,uint breach_time,/*FENCE_MITIGATE*/byte breach_mitigation) { - var msg = new mavlink_scaled_imu2_t(); + var msg = new mavlink_fence_status_t(); - msg.time_boot_ms = time_boot_ms; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.xmag = xmag; - msg.ymag = ymag; - msg.zmag = zmag; - msg.temperature = temperature; + msg.breach_status = breach_status; + msg.breach_count = breach_count; + msg.breach_type = breach_type; + msg.breach_time = breach_time; + msg.breach_mitigation = breach_mitigation; return msg; } - /// Timestamp (time since system boot). [ms] + /// Time (since boot) of last breach. [ms] [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + [Description("Time (since boot) of last breach.")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint breach_time; - /// X acceleration [mG] - [Units("[mG]")] - [Description("X acceleration")] + /// Number of fence breaches. + [Units("")] + [Description("Number of fence breaches.")] //[FieldOffset(4)] - public short xacc; + public ushort breach_count; - /// Y acceleration [mG] - [Units("[mG]")] - [Description("Y acceleration")] + /// Breach status (0 if currently inside fence, 1 if outside). + [Units("")] + [Description("Breach status (0 if currently inside fence, 1 if outside).")] //[FieldOffset(6)] - public short yacc; - - /// Z acceleration [mG] - [Units("[mG]")] - [Description("Z acceleration")] - //[FieldOffset(8)] - public short zacc; - - /// Angular speed around X axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around X axis")] - //[FieldOffset(10)] - public short xgyro; - - /// Angular speed around Y axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around Y axis")] - //[FieldOffset(12)] - public short ygyro; - - /// Angular speed around Z axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around Z axis")] - //[FieldOffset(14)] - public short zgyro; - - /// X Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("X Magnetic field")] - //[FieldOffset(16)] - public short xmag; - - /// Y Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("Y Magnetic field")] - //[FieldOffset(18)] - public short ymag; + public byte breach_status; - /// Z Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("Z Magnetic field")] - //[FieldOffset(20)] - public short zmag; + /// Last breach type. FENCE_BREACH + [Units("")] + [Description("Last breach type.")] + //[FieldOffset(7)] + public /*FENCE_BREACH*/byte breach_type; - /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] - [Units("[cdegC]")] - [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] - //[FieldOffset(22)] - public short temperature; + /// Active action to prevent fence breach FENCE_MITIGATE + [Units("")] + [Description("Active action to prevent fence breach")] + //[FieldOffset(8)] + public /*FENCE_MITIGATE*/byte breach_mitigation; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0. - public struct mavlink_log_request_list_t + /// extensions_start 14 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] + /// Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. + public struct mavlink_mag_cal_report_t { /// packet ordered constructor - public mavlink_log_request_list_t(ushort start,ushort end,byte target_system,byte target_component) + public mavlink_mag_cal_report_t(float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte autosaved,float orientation_confidence,/*MAV_SENSOR_ORIENTATION*/byte old_orientation,/*MAV_SENSOR_ORIENTATION*/byte new_orientation,float scale_factor) { - this.start = start; - this.end = end; - this.target_system = target_system; - this.target_component = target_component; + this.fitness = fitness; + this.ofs_x = ofs_x; + this.ofs_y = ofs_y; + this.ofs_z = ofs_z; + this.diag_x = diag_x; + this.diag_y = diag_y; + this.diag_z = diag_z; + this.offdiag_x = offdiag_x; + this.offdiag_y = offdiag_y; + this.offdiag_z = offdiag_z; + this.compass_id = compass_id; + this.cal_mask = cal_mask; + this.cal_status = cal_status; + this.autosaved = autosaved; + this.orientation_confidence = orientation_confidence; + this.old_orientation = old_orientation; + this.new_orientation = new_orientation; + this.scale_factor = scale_factor; } /// packet xml order - public static mavlink_log_request_list_t PopulateXMLOrder(byte target_system,byte target_component,ushort start,ushort end) + public static mavlink_mag_cal_report_t PopulateXMLOrder(byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte autosaved,float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,float orientation_confidence,/*MAV_SENSOR_ORIENTATION*/byte old_orientation,/*MAV_SENSOR_ORIENTATION*/byte new_orientation,float scale_factor) { - var msg = new mavlink_log_request_list_t(); + var msg = new mavlink_mag_cal_report_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.start = start; - msg.end = end; + msg.compass_id = compass_id; + msg.cal_mask = cal_mask; + msg.cal_status = cal_status; + msg.autosaved = autosaved; + msg.fitness = fitness; + msg.ofs_x = ofs_x; + msg.ofs_y = ofs_y; + msg.ofs_z = ofs_z; + msg.diag_x = diag_x; + msg.diag_y = diag_y; + msg.diag_z = diag_z; + msg.offdiag_x = offdiag_x; + msg.offdiag_y = offdiag_y; + msg.offdiag_z = offdiag_z; + msg.orientation_confidence = orientation_confidence; + msg.old_orientation = old_orientation; + msg.new_orientation = new_orientation; + msg.scale_factor = scale_factor; return msg; } - /// First log id (0 for first available) - [Units("")] - [Description("First log id (0 for first available)")] + /// RMS milligauss residuals. [mgauss] + [Units("[mgauss]")] + [Description("RMS milligauss residuals.")] //[FieldOffset(0)] - public ushort start; + public float fitness; - /// Last log id (0xffff for last available) + /// X offset. [Units("")] - [Description("Last log id (0xffff for last available)")] - //[FieldOffset(2)] - public ushort end; + [Description("X offset.")] + //[FieldOffset(4)] + public float ofs_x; - /// System ID + /// Y offset. [Units("")] - [Description("System ID")] - //[FieldOffset(4)] - public byte target_system; + [Description("Y offset.")] + //[FieldOffset(8)] + public float ofs_y; - /// Component ID + /// Z offset. [Units("")] - [Description("Component ID")] - //[FieldOffset(5)] - public byte target_component; + [Description("Z offset.")] + //[FieldOffset(12)] + public float ofs_z; + + /// X diagonal (matrix 11). + [Units("")] + [Description("X diagonal (matrix 11).")] + //[FieldOffset(16)] + public float diag_x; + + /// Y diagonal (matrix 22). + [Units("")] + [Description("Y diagonal (matrix 22).")] + //[FieldOffset(20)] + public float diag_y; + + /// Z diagonal (matrix 33). + [Units("")] + [Description("Z diagonal (matrix 33).")] + //[FieldOffset(24)] + public float diag_z; + + /// X off-diagonal (matrix 12 and 21). + [Units("")] + [Description("X off-diagonal (matrix 12 and 21).")] + //[FieldOffset(28)] + public float offdiag_x; + + /// Y off-diagonal (matrix 13 and 31). + [Units("")] + [Description("Y off-diagonal (matrix 13 and 31).")] + //[FieldOffset(32)] + public float offdiag_y; + + /// Z off-diagonal (matrix 32 and 23). + [Units("")] + [Description("Z off-diagonal (matrix 32 and 23).")] + //[FieldOffset(36)] + public float offdiag_z; + + /// Compass being calibrated. + [Units("")] + [Description("Compass being calibrated.")] + //[FieldOffset(40)] + public byte compass_id; + + /// Bitmask of compasses being calibrated. bitmask + [Units("")] + [Description("Bitmask of compasses being calibrated.")] + //[FieldOffset(41)] + public byte cal_mask; + + /// Calibration Status. MAG_CAL_STATUS + [Units("")] + [Description("Calibration Status.")] + //[FieldOffset(42)] + public /*MAG_CAL_STATUS*/byte cal_status; + + /// 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. + [Units("")] + [Description("0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.")] + //[FieldOffset(43)] + public byte autosaved; + + /// Confidence in orientation (higher is better). + [Units("")] + [Description("Confidence in orientation (higher is better).")] + //[FieldOffset(44)] + public float orientation_confidence; + + /// orientation before calibration. MAV_SENSOR_ORIENTATION + [Units("")] + [Description("orientation before calibration.")] + //[FieldOffset(48)] + public /*MAV_SENSOR_ORIENTATION*/byte old_orientation; + + /// orientation after calibration. MAV_SENSOR_ORIENTATION + [Units("")] + [Description("orientation after calibration.")] + //[FieldOffset(49)] + public /*MAV_SENSOR_ORIENTATION*/byte new_orientation; + + /// field radius correction factor + [Units("")] + [Description("field radius correction factor")] + //[FieldOffset(50)] + public float scale_factor; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - /// Reply to LOG_REQUEST_LIST - public struct mavlink_log_entry_t + /// extensions_start 17 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=73)] + /// EFI status output + public struct mavlink_efi_status_t { /// packet ordered constructor - public mavlink_log_entry_t(uint time_utc,uint size,ushort id,ushort num_logs,ushort last_log_num) + public mavlink_efi_status_t(float ecu_index,float rpm,float fuel_consumed,float fuel_flow,float engine_load,float throttle_position,float spark_dwell_time,float barometric_pressure,float intake_manifold_pressure,float intake_manifold_temperature,float cylinder_head_temperature,float ignition_timing,float injection_time,float exhaust_gas_temperature,float throttle_out,float pt_compensation,byte health,float ignition_voltage,float fuel_pressure) { - this.time_utc = time_utc; - this.size = size; - this.id = id; - this.num_logs = num_logs; - this.last_log_num = last_log_num; + this.ecu_index = ecu_index; + this.rpm = rpm; + this.fuel_consumed = fuel_consumed; + this.fuel_flow = fuel_flow; + this.engine_load = engine_load; + this.throttle_position = throttle_position; + this.spark_dwell_time = spark_dwell_time; + this.barometric_pressure = barometric_pressure; + this.intake_manifold_pressure = intake_manifold_pressure; + this.intake_manifold_temperature = intake_manifold_temperature; + this.cylinder_head_temperature = cylinder_head_temperature; + this.ignition_timing = ignition_timing; + this.injection_time = injection_time; + this.exhaust_gas_temperature = exhaust_gas_temperature; + this.throttle_out = throttle_out; + this.pt_compensation = pt_compensation; + this.health = health; + this.ignition_voltage = ignition_voltage; + this.fuel_pressure = fuel_pressure; } /// packet xml order - public static mavlink_log_entry_t PopulateXMLOrder(ushort id,ushort num_logs,ushort last_log_num,uint time_utc,uint size) + public static mavlink_efi_status_t PopulateXMLOrder(byte health,float ecu_index,float rpm,float fuel_consumed,float fuel_flow,float engine_load,float throttle_position,float spark_dwell_time,float barometric_pressure,float intake_manifold_pressure,float intake_manifold_temperature,float cylinder_head_temperature,float ignition_timing,float injection_time,float exhaust_gas_temperature,float throttle_out,float pt_compensation,float ignition_voltage,float fuel_pressure) { - var msg = new mavlink_log_entry_t(); + var msg = new mavlink_efi_status_t(); - msg.id = id; - msg.num_logs = num_logs; - msg.last_log_num = last_log_num; - msg.time_utc = time_utc; - msg.size = size; + msg.health = health; + msg.ecu_index = ecu_index; + msg.rpm = rpm; + msg.fuel_consumed = fuel_consumed; + msg.fuel_flow = fuel_flow; + msg.engine_load = engine_load; + msg.throttle_position = throttle_position; + msg.spark_dwell_time = spark_dwell_time; + msg.barometric_pressure = barometric_pressure; + msg.intake_manifold_pressure = intake_manifold_pressure; + msg.intake_manifold_temperature = intake_manifold_temperature; + msg.cylinder_head_temperature = cylinder_head_temperature; + msg.ignition_timing = ignition_timing; + msg.injection_time = injection_time; + msg.exhaust_gas_temperature = exhaust_gas_temperature; + msg.throttle_out = throttle_out; + msg.pt_compensation = pt_compensation; + msg.ignition_voltage = ignition_voltage; + msg.fuel_pressure = fuel_pressure; return msg; } - /// UTC timestamp of log since 1970, or 0 if not available [s] - [Units("[s]")] - [Description("UTC timestamp of log since 1970, or 0 if not available")] + /// ECU index + [Units("")] + [Description("ECU index")] //[FieldOffset(0)] - public uint time_utc; + public float ecu_index; - /// Size of the log (may be approximate) [bytes] - [Units("[bytes]")] - [Description("Size of the log (may be approximate)")] + /// RPM + [Units("")] + [Description("RPM")] //[FieldOffset(4)] - public uint size; + public float rpm; - /// Log id - [Units("")] - [Description("Log id")] + /// Fuel consumed [cm^3] + [Units("[cm^3]")] + [Description("Fuel consumed")] //[FieldOffset(8)] - public ushort id; + public float fuel_consumed; - /// Total number of logs + /// Fuel flow rate [cm^3/min] + [Units("[cm^3/min]")] + [Description("Fuel flow rate")] + //[FieldOffset(12)] + public float fuel_flow; + + /// Engine load [%] + [Units("[%]")] + [Description("Engine load")] + //[FieldOffset(16)] + public float engine_load; + + /// Throttle position [%] + [Units("[%]")] + [Description("Throttle position")] + //[FieldOffset(20)] + public float throttle_position; + + /// Spark dwell time [ms] + [Units("[ms]")] + [Description("Spark dwell time")] + //[FieldOffset(24)] + public float spark_dwell_time; + + /// Barometric pressure [kPa] + [Units("[kPa]")] + [Description("Barometric pressure")] + //[FieldOffset(28)] + public float barometric_pressure; + + /// Intake manifold pressure( [kPa] + [Units("[kPa]")] + [Description("Intake manifold pressure(")] + //[FieldOffset(32)] + public float intake_manifold_pressure; + + /// Intake manifold temperature [degC] + [Units("[degC]")] + [Description("Intake manifold temperature")] + //[FieldOffset(36)] + public float intake_manifold_temperature; + + /// Cylinder head temperature [degC] + [Units("[degC]")] + [Description("Cylinder head temperature")] + //[FieldOffset(40)] + public float cylinder_head_temperature; + + /// Ignition timing (Crank angle degrees) [deg] + [Units("[deg]")] + [Description("Ignition timing (Crank angle degrees)")] + //[FieldOffset(44)] + public float ignition_timing; + + /// Injection time [ms] + [Units("[ms]")] + [Description("Injection time")] + //[FieldOffset(48)] + public float injection_time; + + /// Exhaust gas temperature [degC] + [Units("[degC]")] + [Description("Exhaust gas temperature")] + //[FieldOffset(52)] + public float exhaust_gas_temperature; + + /// Output throttle [%] + [Units("[%]")] + [Description("Output throttle")] + //[FieldOffset(56)] + public float throttle_out; + + /// Pressure/temperature compensation [Units("")] - [Description("Total number of logs")] - //[FieldOffset(10)] - public ushort num_logs; + [Description("Pressure/temperature compensation")] + //[FieldOffset(60)] + public float pt_compensation; + + /// EFI health status + [Units("")] + [Description("EFI health status")] + //[FieldOffset(64)] + public byte health; + + /// Supply voltage to EFI sparking system. Zero in this value means 'unknown', so if the supply voltage really is zero volts use 0.0001 instead. [V] + [Units("[V]")] + [Description("Supply voltage to EFI sparking system. Zero in this value means 'unknown', so if the supply voltage really is zero volts use 0.0001 instead.")] + //[FieldOffset(65)] + public float ignition_voltage; - /// High log number - [Units("")] - [Description("High log number")] - //[FieldOffset(12)] - public ushort last_log_num; + /// Fuel pressure. Zero in this value means 'unknown', so if the fuel pressure really is zero kPa use 0.0001 instead. [kPa] + [Units("[kPa]")] + [Description("Fuel pressure. Zero in this value means 'unknown', so if the fuel pressure really is zero kPa use 0.0001 instead.")] + //[FieldOffset(69)] + public float fuel_pressure; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - /// Request a chunk of a log - public struct mavlink_log_request_data_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. + public struct mavlink_estimator_status_t { /// packet ordered constructor - public mavlink_log_request_data_t(uint ofs,uint count,ushort id,byte target_system,byte target_component) + public mavlink_estimator_status_t(ulong time_usec,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy,/*ESTIMATOR_STATUS_FLAGS*/ushort flags) { - this.ofs = ofs; - this.count = count; - this.id = id; - this.target_system = target_system; - this.target_component = target_component; + this.time_usec = time_usec; + this.vel_ratio = vel_ratio; + this.pos_horiz_ratio = pos_horiz_ratio; + this.pos_vert_ratio = pos_vert_ratio; + this.mag_ratio = mag_ratio; + this.hagl_ratio = hagl_ratio; + this.tas_ratio = tas_ratio; + this.pos_horiz_accuracy = pos_horiz_accuracy; + this.pos_vert_accuracy = pos_vert_accuracy; + this.flags = flags; } /// packet xml order - public static mavlink_log_request_data_t PopulateXMLOrder(byte target_system,byte target_component,ushort id,uint ofs,uint count) + public static mavlink_estimator_status_t PopulateXMLOrder(ulong time_usec,/*ESTIMATOR_STATUS_FLAGS*/ushort flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) { - var msg = new mavlink_log_request_data_t(); + var msg = new mavlink_estimator_status_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.id = id; - msg.ofs = ofs; - msg.count = count; + msg.time_usec = time_usec; + msg.flags = flags; + msg.vel_ratio = vel_ratio; + msg.pos_horiz_ratio = pos_horiz_ratio; + msg.pos_vert_ratio = pos_vert_ratio; + msg.mag_ratio = mag_ratio; + msg.hagl_ratio = hagl_ratio; + msg.tas_ratio = tas_ratio; + msg.pos_horiz_accuracy = pos_horiz_accuracy; + msg.pos_vert_accuracy = pos_vert_accuracy; return msg; } - /// Offset into the log - [Units("")] - [Description("Offset into the log")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint ofs; - - /// Number of bytes [bytes] - [Units("[bytes]")] - [Description("Number of bytes")] - //[FieldOffset(4)] - public uint count; + public ulong time_usec; - /// Log id (from LOG_ENTRY reply) + /// Velocity innovation test ratio [Units("")] - [Description("Log id (from LOG_ENTRY reply)")] + [Description("Velocity innovation test ratio")] //[FieldOffset(8)] - public ushort id; + public float vel_ratio; - /// System ID + /// Horizontal position innovation test ratio [Units("")] - [Description("System ID")] - //[FieldOffset(10)] - public byte target_system; + [Description("Horizontal position innovation test ratio")] + //[FieldOffset(12)] + public float pos_horiz_ratio; - /// Component ID + /// Vertical position innovation test ratio [Units("")] - [Description("Component ID")] - //[FieldOffset(11)] - public byte target_component; - }; - - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=97)] - /// Reply to LOG_REQUEST_DATA - public struct mavlink_log_data_t - { - /// packet ordered constructor - public mavlink_log_data_t(uint ofs,ushort id,byte count,byte[] data) - { - this.ofs = ofs; - this.id = id; - this.count = count; - this.data = data; - - } - - /// packet xml order - public static mavlink_log_data_t PopulateXMLOrder(ushort id,uint ofs,byte count,byte[] data) - { - var msg = new mavlink_log_data_t(); + [Description("Vertical position innovation test ratio")] + //[FieldOffset(16)] + public float pos_vert_ratio; - msg.id = id; - msg.ofs = ofs; - msg.count = count; - msg.data = data; - - return msg; - } - + /// Magnetometer innovation test ratio + [Units("")] + [Description("Magnetometer innovation test ratio")] + //[FieldOffset(20)] + public float mag_ratio; - /// Offset into the log + /// Height above terrain innovation test ratio [Units("")] - [Description("Offset into the log")] - //[FieldOffset(0)] - public uint ofs; + [Description("Height above terrain innovation test ratio")] + //[FieldOffset(24)] + public float hagl_ratio; - /// Log id (from LOG_ENTRY reply) + /// True airspeed innovation test ratio [Units("")] - [Description("Log id (from LOG_ENTRY reply)")] - //[FieldOffset(4)] - public ushort id; + [Description("True airspeed innovation test ratio")] + //[FieldOffset(28)] + public float tas_ratio; - /// Number of bytes (zero for end of log) [bytes] - [Units("[bytes]")] - [Description("Number of bytes (zero for end of log)")] - //[FieldOffset(6)] - public byte count; + /// Horizontal position 1-STD accuracy relative to the EKF local origin [m] + [Units("[m]")] + [Description("Horizontal position 1-STD accuracy relative to the EKF local origin")] + //[FieldOffset(32)] + public float pos_horiz_accuracy; - /// log data + /// Vertical position 1-STD accuracy relative to the EKF local origin [m] + [Units("[m]")] + [Description("Vertical position 1-STD accuracy relative to the EKF local origin")] + //[FieldOffset(36)] + public float pos_vert_accuracy; + + /// Bitmap indicating which EKF outputs are valid. ESTIMATOR_STATUS_FLAGS bitmask [Units("")] - [Description("log data")] - //[FieldOffset(7)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=90)] - public byte[] data; + [Description("Bitmap indicating which EKF outputs are valid.")] + //[FieldOffset(40)] + public /*ESTIMATOR_STATUS_FLAGS*/ushort flags; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Erase all logs - public struct mavlink_log_erase_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] + /// Wind covariance estimate from vehicle. + public struct mavlink_wind_cov_t { /// packet ordered constructor - public mavlink_log_erase_t(byte target_system,byte target_component) + public mavlink_wind_cov_t(ulong time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) { - this.target_system = target_system; - this.target_component = target_component; + this.time_usec = time_usec; + this.wind_x = wind_x; + this.wind_y = wind_y; + this.wind_z = wind_z; + this.var_horiz = var_horiz; + this.var_vert = var_vert; + this.wind_alt = wind_alt; + this.horiz_accuracy = horiz_accuracy; + this.vert_accuracy = vert_accuracy; } /// packet xml order - public static mavlink_log_erase_t PopulateXMLOrder(byte target_system,byte target_component) + public static mavlink_wind_cov_t PopulateXMLOrder(ulong time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) { - var msg = new mavlink_log_erase_t(); + var msg = new mavlink_wind_cov_t(); - msg.target_system = target_system; - msg.target_component = target_component; + msg.time_usec = time_usec; + msg.wind_x = wind_x; + msg.wind_y = wind_y; + msg.wind_z = wind_z; + msg.var_horiz = var_horiz; + msg.var_vert = var_vert; + msg.wind_alt = wind_alt; + msg.horiz_accuracy = horiz_accuracy; + msg.vert_accuracy = vert_accuracy; return msg; } - /// System ID - [Units("")] - [Description("System ID")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public byte target_system; + public ulong time_usec; - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + /// Wind in X (NED) direction [m/s] + [Units("[m/s]")] + [Description("Wind in X (NED) direction")] + //[FieldOffset(8)] + public float wind_x; + + /// Wind in Y (NED) direction [m/s] + [Units("[m/s]")] + [Description("Wind in Y (NED) direction")] + //[FieldOffset(12)] + public float wind_y; + + /// Wind in Z (NED) direction [m/s] + [Units("[m/s]")] + [Description("Wind in Z (NED) direction")] + //[FieldOffset(16)] + public float wind_z; + + /// Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. [m/s] + [Units("[m/s]")] + [Description("Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.")] + //[FieldOffset(20)] + public float var_horiz; + + /// Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. [m/s] + [Units("[m/s]")] + [Description("Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.")] + //[FieldOffset(24)] + public float var_vert; + + /// Altitude (MSL) that this measurement was taken at [m] + [Units("[m]")] + [Description("Altitude (MSL) that this measurement was taken at")] + //[FieldOffset(28)] + public float wind_alt; + + /// Horizontal speed 1-STD accuracy [m] + [Units("[m]")] + [Description("Horizontal speed 1-STD accuracy")] + //[FieldOffset(32)] + public float horiz_accuracy; + + /// Vertical speed 1-STD accuracy [m] + [Units("[m]")] + [Description("Vertical speed 1-STD accuracy")] + //[FieldOffset(36)] + public float vert_accuracy; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Stop log transfer and resume normal logging - public struct mavlink_log_request_end_t + /// extensions_start 18 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=65)] + /// GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system. + public struct mavlink_gps_input_t { /// packet ordered constructor - public mavlink_log_request_end_t(byte target_system,byte target_component) + public mavlink_gps_input_t(ulong time_usec,uint time_week_ms,int lat,int lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,/*GPS_INPUT_IGNORE_FLAGS*/ushort ignore_flags,ushort time_week,byte gps_id,byte fix_type,byte satellites_visible,ushort yaw) { - this.target_system = target_system; - this.target_component = target_component; + this.time_usec = time_usec; + this.time_week_ms = time_week_ms; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.hdop = hdop; + this.vdop = vdop; + this.vn = vn; + this.ve = ve; + this.vd = vd; + this.speed_accuracy = speed_accuracy; + this.horiz_accuracy = horiz_accuracy; + this.vert_accuracy = vert_accuracy; + this.ignore_flags = ignore_flags; + this.time_week = time_week; + this.gps_id = gps_id; + this.fix_type = fix_type; + this.satellites_visible = satellites_visible; + this.yaw = yaw; } /// packet xml order - public static mavlink_log_request_end_t PopulateXMLOrder(byte target_system,byte target_component) + public static mavlink_gps_input_t PopulateXMLOrder(ulong time_usec,byte gps_id,/*GPS_INPUT_IGNORE_FLAGS*/ushort ignore_flags,uint time_week_ms,ushort time_week,byte fix_type,int lat,int lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,byte satellites_visible,ushort yaw) { - var msg = new mavlink_log_request_end_t(); + var msg = new mavlink_gps_input_t(); - msg.target_system = target_system; - msg.target_component = target_component; + msg.time_usec = time_usec; + msg.gps_id = gps_id; + msg.ignore_flags = ignore_flags; + msg.time_week_ms = time_week_ms; + msg.time_week = time_week; + msg.fix_type = fix_type; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.hdop = hdop; + msg.vdop = vdop; + msg.vn = vn; + msg.ve = ve; + msg.vd = vd; + msg.speed_accuracy = speed_accuracy; + msg.horiz_accuracy = horiz_accuracy; + msg.vert_accuracy = vert_accuracy; + msg.satellites_visible = satellites_visible; + msg.yaw = yaw; return msg; } - /// System ID - [Units("")] - [Description("System ID")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public byte target_system; + public ulong time_usec; - /// Component ID + /// GPS time (from start of GPS week) [ms] + [Units("[ms]")] + [Description("GPS time (from start of GPS week)")] + //[FieldOffset(8)] + public uint time_week_ms; + + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] + //[FieldOffset(12)] + public int lat; + + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] + //[FieldOffset(16)] + public int lon; + + /// Altitude (MSL). Positive for up. [m] + [Units("[m]")] + [Description("Altitude (MSL). Positive for up.")] + //[FieldOffset(20)] + public float alt; + + /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] + //[FieldOffset(24)] + public float hdop; + + /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + [Units("")] + [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + //[FieldOffset(28)] + public float vdop; + + /// GPS velocity in north direction in earth-fixed NED frame [m/s] + [Units("[m/s]")] + [Description("GPS velocity in north direction in earth-fixed NED frame")] + //[FieldOffset(32)] + public float vn; + + /// GPS velocity in east direction in earth-fixed NED frame [m/s] + [Units("[m/s]")] + [Description("GPS velocity in east direction in earth-fixed NED frame")] + //[FieldOffset(36)] + public float ve; + + /// GPS velocity in down direction in earth-fixed NED frame [m/s] + [Units("[m/s]")] + [Description("GPS velocity in down direction in earth-fixed NED frame")] + //[FieldOffset(40)] + public float vd; + + /// GPS speed accuracy [m/s] + [Units("[m/s]")] + [Description("GPS speed accuracy")] + //[FieldOffset(44)] + public float speed_accuracy; + + /// GPS horizontal accuracy [m] + [Units("[m]")] + [Description("GPS horizontal accuracy")] + //[FieldOffset(48)] + public float horiz_accuracy; + + /// GPS vertical accuracy [m] + [Units("[m]")] + [Description("GPS vertical accuracy")] + //[FieldOffset(52)] + public float vert_accuracy; + + /// Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. GPS_INPUT_IGNORE_FLAGS bitmask + [Units("")] + [Description("Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.")] + //[FieldOffset(56)] + public /*GPS_INPUT_IGNORE_FLAGS*/ushort ignore_flags; + + /// GPS week number + [Units("")] + [Description("GPS week number")] + //[FieldOffset(58)] + public ushort time_week; + + /// ID of the GPS for multiple GPS inputs + [Units("")] + [Description("ID of the GPS for multiple GPS inputs")] + //[FieldOffset(60)] + public byte gps_id; + + /// 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK + [Units("")] + [Description("0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK")] + //[FieldOffset(61)] + public byte fix_type; + + /// Number of satellites visible. + [Units("")] + [Description("Number of satellites visible.")] + //[FieldOffset(62)] + public byte satellites_visible; + + /// Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north [cdeg] + [Units("[cdeg]")] + [Description("Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north")] + //[FieldOffset(63)] + public ushort yaw; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=113)] - /// Data for injecting into the onboard GPS (used for DGPS) - public struct mavlink_gps_inject_data_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=182)] + /// RTCM message for injecting into the onboard GPS (used for DGPS) + public struct mavlink_gps_rtcm_data_t { /// packet ordered constructor - public mavlink_gps_inject_data_t(byte target_system,byte target_component,byte len,byte[] data) + public mavlink_gps_rtcm_data_t(byte flags,byte len,byte[] data) { - this.target_system = target_system; - this.target_component = target_component; + this.flags = flags; this.len = len; this.data = data; } /// packet xml order - public static mavlink_gps_inject_data_t PopulateXMLOrder(byte target_system,byte target_component,byte len,byte[] data) + public static mavlink_gps_rtcm_data_t PopulateXMLOrder(byte flags,byte len,byte[] data) { - var msg = new mavlink_gps_inject_data_t(); + var msg = new mavlink_gps_rtcm_data_t(); - msg.target_system = target_system; - msg.target_component = target_component; + msg.flags = flags; msg.len = len; msg.data = data; @@ -20572,1186 +26423,1283 @@ public static mavlink_gps_inject_data_t PopulateXMLOrder(byte target_system,byte } - /// System ID + /// LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. [Units("")] - [Description("System ID")] + [Description("LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.")] //[FieldOffset(0)] - public byte target_system; - - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; + public byte flags; - /// Data length [bytes] + /// data length [bytes] [Units("[bytes]")] - [Description("Data length")] - //[FieldOffset(2)] + [Description("data length")] + //[FieldOffset(1)] public byte len; - /// Raw data (110 is enough for 12 satellites of RTCMv2) + /// RTCM message (may be fragmented) [Units("")] - [Description("Raw data (110 is enough for 12 satellites of RTCMv2)")] - //[FieldOffset(3)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=110)] + [Description("RTCM message (may be fragmented)")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=180)] public byte[] data; }; - - /// extensions_start 12 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=57)] - /// Second GPS data. - public struct mavlink_gps2_raw_t + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] + /// Message appropriate for high latency connections like Iridium + public struct mavlink_high_latency_t { /// packet ordered constructor - public mavlink_gps2_raw_t(ulong time_usec,int lat,int lon,int alt,uint dgps_age,ushort eph,ushort epv,ushort vel,ushort cog,/*GPS_FIX_TYPE*/byte fix_type,byte satellites_visible,byte dgps_numch,ushort yaw,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc) + public mavlink_high_latency_t(uint custom_mode,int latitude,int longitude,short roll,short pitch,ushort heading,short heading_sp,short altitude_amsl,short altitude_sp,ushort wp_distance,/*MAV_MODE_FLAG*/byte base_mode,/*MAV_LANDED_STATE*/byte landed_state,sbyte throttle,byte airspeed,byte airspeed_sp,byte groundspeed,sbyte climb_rate,byte gps_nsat,/*GPS_FIX_TYPE*/byte gps_fix_type,byte battery_remaining,sbyte temperature,sbyte temperature_air,byte failsafe,byte wp_num) { - this.time_usec = time_usec; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.dgps_age = dgps_age; - this.eph = eph; - this.epv = epv; - this.vel = vel; - this.cog = cog; - this.fix_type = fix_type; - this.satellites_visible = satellites_visible; - this.dgps_numch = dgps_numch; - this.yaw = yaw; - this.alt_ellipsoid = alt_ellipsoid; - this.h_acc = h_acc; - this.v_acc = v_acc; - this.vel_acc = vel_acc; - this.hdg_acc = hdg_acc; + this.custom_mode = custom_mode; + this.latitude = latitude; + this.longitude = longitude; + this.roll = roll; + this.pitch = pitch; + this.heading = heading; + this.heading_sp = heading_sp; + this.altitude_amsl = altitude_amsl; + this.altitude_sp = altitude_sp; + this.wp_distance = wp_distance; + this.base_mode = base_mode; + this.landed_state = landed_state; + this.throttle = throttle; + this.airspeed = airspeed; + this.airspeed_sp = airspeed_sp; + this.groundspeed = groundspeed; + this.climb_rate = climb_rate; + this.gps_nsat = gps_nsat; + this.gps_fix_type = gps_fix_type; + this.battery_remaining = battery_remaining; + this.temperature = temperature; + this.temperature_air = temperature_air; + this.failsafe = failsafe; + this.wp_num = wp_num; } /// packet xml order - public static mavlink_gps2_raw_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_TYPE*/byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,byte satellites_visible,byte dgps_numch,uint dgps_age,ushort yaw,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc) + public static mavlink_high_latency_t PopulateXMLOrder(/*MAV_MODE_FLAG*/byte base_mode,uint custom_mode,/*MAV_LANDED_STATE*/byte landed_state,short roll,short pitch,ushort heading,sbyte throttle,short heading_sp,int latitude,int longitude,short altitude_amsl,short altitude_sp,byte airspeed,byte airspeed_sp,byte groundspeed,sbyte climb_rate,byte gps_nsat,/*GPS_FIX_TYPE*/byte gps_fix_type,byte battery_remaining,sbyte temperature,sbyte temperature_air,byte failsafe,byte wp_num,ushort wp_distance) { - var msg = new mavlink_gps2_raw_t(); + var msg = new mavlink_high_latency_t(); - msg.time_usec = time_usec; - msg.fix_type = fix_type; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.eph = eph; - msg.epv = epv; - msg.vel = vel; - msg.cog = cog; - msg.satellites_visible = satellites_visible; - msg.dgps_numch = dgps_numch; - msg.dgps_age = dgps_age; - msg.yaw = yaw; - msg.alt_ellipsoid = alt_ellipsoid; - msg.h_acc = h_acc; - msg.v_acc = v_acc; - msg.vel_acc = vel_acc; - msg.hdg_acc = hdg_acc; + msg.base_mode = base_mode; + msg.custom_mode = custom_mode; + msg.landed_state = landed_state; + msg.roll = roll; + msg.pitch = pitch; + msg.heading = heading; + msg.throttle = throttle; + msg.heading_sp = heading_sp; + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude_amsl = altitude_amsl; + msg.altitude_sp = altitude_sp; + msg.airspeed = airspeed; + msg.airspeed_sp = airspeed_sp; + msg.groundspeed = groundspeed; + msg.climb_rate = climb_rate; + msg.gps_nsat = gps_nsat; + msg.gps_fix_type = gps_fix_type; + msg.battery_remaining = battery_remaining; + msg.temperature = temperature; + msg.temperature_air = temperature_air; + msg.failsafe = failsafe; + msg.wp_num = wp_num; + msg.wp_distance = wp_distance; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// A bitfield for use for autopilot-specific flags. bitmask + [Units("")] + [Description("A bitfield for use for autopilot-specific flags.")] //[FieldOffset(0)] - public ulong time_usec; + public uint custom_mode; - /// Latitude (WGS84) [degE7] + /// Latitude [degE7] [Units("[degE7]")] - [Description("Latitude (WGS84)")] - //[FieldOffset(8)] - public int lat; + [Description("Latitude")] + //[FieldOffset(4)] + public int latitude; - /// Longitude (WGS84) [degE7] + /// Longitude [degE7] [Units("[degE7]")] - [Description("Longitude (WGS84)")] + [Description("Longitude")] + //[FieldOffset(8)] + public int longitude; + + /// roll [cdeg] + [Units("[cdeg]")] + [Description("roll")] //[FieldOffset(12)] - public int lon; + public short roll; - /// Altitude (MSL). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up.")] + /// pitch [cdeg] + [Units("[cdeg]")] + [Description("pitch")] + //[FieldOffset(14)] + public short pitch; + + /// heading [cdeg] + [Units("[cdeg]")] + [Description("heading")] //[FieldOffset(16)] - public int alt; + public ushort heading; - /// Age of DGPS info [ms] - [Units("[ms]")] - [Description("Age of DGPS info")] + /// heading setpoint [cdeg] + [Units("[cdeg]")] + [Description("heading setpoint")] + //[FieldOffset(18)] + public short heading_sp; + + /// Altitude above mean sea level [m] + [Units("[m]")] + [Description("Altitude above mean sea level")] //[FieldOffset(20)] - public uint dgps_age; + public short altitude_amsl; - /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - [Units("")] - [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] + /// Altitude setpoint relative to the home position [m] + [Units("[m]")] + [Description("Altitude setpoint relative to the home position")] + //[FieldOffset(22)] + public short altitude_sp; + + /// distance to target [m] + [Units("[m]")] + [Description("distance to target")] //[FieldOffset(24)] - public ushort eph; + public ushort wp_distance; - /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + /// Bitmap of enabled system modes. MAV_MODE_FLAG bitmask [Units("")] - [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + [Description("Bitmap of enabled system modes.")] //[FieldOffset(26)] - public ushort epv; + public /*MAV_MODE_FLAG*/byte base_mode; - /// GPS ground speed. If unknown, set to: UINT16_MAX [cm/s] - [Units("[cm/s]")] - [Description("GPS ground speed. If unknown, set to: UINT16_MAX")] + /// The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. MAV_LANDED_STATE + [Units("")] + [Description("The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.")] + //[FieldOffset(27)] + public /*MAV_LANDED_STATE*/byte landed_state; + + /// throttle (percentage) [%] + [Units("[%]")] + [Description("throttle (percentage)")] //[FieldOffset(28)] - public ushort vel; + public sbyte throttle; - /// Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX [cdeg] - [Units("[cdeg]")] - [Description("Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX")] + /// airspeed [m/s] + [Units("[m/s]")] + [Description("airspeed")] + //[FieldOffset(29)] + public byte airspeed; + + /// airspeed setpoint [m/s] + [Units("[m/s]")] + [Description("airspeed setpoint")] //[FieldOffset(30)] - public ushort cog; + public byte airspeed_sp; - /// GPS fix type. GPS_FIX_TYPE - [Units("")] - [Description("GPS fix type.")] + /// groundspeed [m/s] + [Units("[m/s]")] + [Description("groundspeed")] + //[FieldOffset(31)] + public byte groundspeed; + + /// climb rate [m/s] + [Units("[m/s]")] + [Description("climb rate")] //[FieldOffset(32)] - public /*GPS_FIX_TYPE*/byte fix_type; + public sbyte climb_rate; /// Number of satellites visible. If unknown, set to 255 [Units("")] [Description("Number of satellites visible. If unknown, set to 255")] //[FieldOffset(33)] - public byte satellites_visible; + public byte gps_nsat; - /// Number of DGPS satellites + /// GPS Fix type. GPS_FIX_TYPE [Units("")] - [Description("Number of DGPS satellites")] + [Description("GPS Fix type.")] //[FieldOffset(34)] - public byte dgps_numch; + public /*GPS_FIX_TYPE*/byte gps_fix_type; - /// Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. [cdeg] - [Units("[cdeg]")] - [Description("Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.")] + /// Remaining battery (percentage) [%] + [Units("[%]")] + [Description("Remaining battery (percentage)")] //[FieldOffset(35)] - public ushort yaw; - - /// Altitude (above WGS84, EGM96 ellipsoid). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (above WGS84, EGM96 ellipsoid). Positive for up.")] - //[FieldOffset(37)] - public int alt_ellipsoid; + public byte battery_remaining; - /// Position uncertainty. [mm] - [Units("[mm]")] - [Description("Position uncertainty.")] - //[FieldOffset(41)] - public uint h_acc; + /// Autopilot temperature (degrees C) [degC] + [Units("[degC]")] + [Description("Autopilot temperature (degrees C)")] + //[FieldOffset(36)] + public sbyte temperature; - /// Altitude uncertainty. [mm] - [Units("[mm]")] - [Description("Altitude uncertainty.")] - //[FieldOffset(45)] - public uint v_acc; + /// Air temperature (degrees C) from airspeed sensor [degC] + [Units("[degC]")] + [Description("Air temperature (degrees C) from airspeed sensor")] + //[FieldOffset(37)] + public sbyte temperature_air; - /// Speed uncertainty. [mm] - [Units("[mm]")] - [Description("Speed uncertainty.")] - //[FieldOffset(49)] - public uint vel_acc; + /// failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) + [Units("")] + [Description("failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)")] + //[FieldOffset(38)] + public byte failsafe; - /// Heading / track uncertainty [degE5] - [Units("[degE5]")] - [Description("Heading / track uncertainty")] - //[FieldOffset(53)] - public uint hdg_acc; + /// current waypoint number + [Units("")] + [Description("current waypoint number")] + //[FieldOffset(39)] + public byte wp_num; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// Power supply status - public struct mavlink_power_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Message appropriate for high latency connections like Iridium (version 2) + public struct mavlink_high_latency2_t { /// packet ordered constructor - public mavlink_power_status_t(ushort Vcc,ushort Vservo,/*MAV_POWER_STATUS*/ushort flags) + public mavlink_high_latency2_t(uint timestamp,int latitude,int longitude,ushort custom_mode,short altitude,short target_altitude,ushort target_distance,ushort wp_num,/*HL_FAILURE_FLAG*/ushort failure_flags,/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,byte heading,byte target_heading,byte throttle,byte airspeed,byte airspeed_sp,byte groundspeed,byte windspeed,byte wind_heading,byte eph,byte epv,sbyte temperature_air,sbyte climb_rate,sbyte battery,sbyte custom0,sbyte custom1,sbyte custom2) { - this.Vcc = Vcc; - this.Vservo = Vservo; - this.flags = flags; + this.timestamp = timestamp; + this.latitude = latitude; + this.longitude = longitude; + this.custom_mode = custom_mode; + this.altitude = altitude; + this.target_altitude = target_altitude; + this.target_distance = target_distance; + this.wp_num = wp_num; + this.failure_flags = failure_flags; + this.type = type; + this.autopilot = autopilot; + this.heading = heading; + this.target_heading = target_heading; + this.throttle = throttle; + this.airspeed = airspeed; + this.airspeed_sp = airspeed_sp; + this.groundspeed = groundspeed; + this.windspeed = windspeed; + this.wind_heading = wind_heading; + this.eph = eph; + this.epv = epv; + this.temperature_air = temperature_air; + this.climb_rate = climb_rate; + this.battery = battery; + this.custom0 = custom0; + this.custom1 = custom1; + this.custom2 = custom2; } /// packet xml order - public static mavlink_power_status_t PopulateXMLOrder(ushort Vcc,ushort Vservo,/*MAV_POWER_STATUS*/ushort flags) + public static mavlink_high_latency2_t PopulateXMLOrder(uint timestamp,/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,ushort custom_mode,int latitude,int longitude,short altitude,short target_altitude,byte heading,byte target_heading,ushort target_distance,byte throttle,byte airspeed,byte airspeed_sp,byte groundspeed,byte windspeed,byte wind_heading,byte eph,byte epv,sbyte temperature_air,sbyte climb_rate,sbyte battery,ushort wp_num,/*HL_FAILURE_FLAG*/ushort failure_flags,sbyte custom0,sbyte custom1,sbyte custom2) { - var msg = new mavlink_power_status_t(); + var msg = new mavlink_high_latency2_t(); - msg.Vcc = Vcc; - msg.Vservo = Vservo; - msg.flags = flags; + msg.timestamp = timestamp; + msg.type = type; + msg.autopilot = autopilot; + msg.custom_mode = custom_mode; + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude = altitude; + msg.target_altitude = target_altitude; + msg.heading = heading; + msg.target_heading = target_heading; + msg.target_distance = target_distance; + msg.throttle = throttle; + msg.airspeed = airspeed; + msg.airspeed_sp = airspeed_sp; + msg.groundspeed = groundspeed; + msg.windspeed = windspeed; + msg.wind_heading = wind_heading; + msg.eph = eph; + msg.epv = epv; + msg.temperature_air = temperature_air; + msg.climb_rate = climb_rate; + msg.battery = battery; + msg.wp_num = wp_num; + msg.failure_flags = failure_flags; + msg.custom0 = custom0; + msg.custom1 = custom1; + msg.custom2 = custom2; return msg; } - /// 5V rail voltage. [mV] - [Units("[mV]")] - [Description("5V rail voltage.")] + /// Timestamp (milliseconds since boot or Unix epoch) [ms] + [Units("[ms]")] + [Description("Timestamp (milliseconds since boot or Unix epoch)")] //[FieldOffset(0)] - public ushort Vcc; + public uint timestamp; - /// Servo rail voltage. [mV] - [Units("[mV]")] - [Description("Servo rail voltage.")] - //[FieldOffset(2)] - public ushort Vservo; + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] + //[FieldOffset(4)] + public int latitude; - /// Bitmap of power supply status flags. MAV_POWER_STATUS bitmask + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] + //[FieldOffset(8)] + public int longitude; + + /// A bitfield for use for autopilot-specific flags (2 byte version). bitmask [Units("")] - [Description("Bitmap of power supply status flags.")] - //[FieldOffset(4)] - public /*MAV_POWER_STATUS*/ushort flags; - }; + [Description("A bitfield for use for autopilot-specific flags (2 byte version).")] + //[FieldOffset(12)] + public ushort custom_mode; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=79)] - /// Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. - public struct mavlink_serial_control_t - { - /// packet ordered constructor - public mavlink_serial_control_t(uint baudrate,ushort timeout,/*SERIAL_CONTROL_DEV*/byte device,/*SERIAL_CONTROL_FLAG*/byte flags,byte count,byte[] data) - { - this.baudrate = baudrate; - this.timeout = timeout; - this.device = device; - this.flags = flags; - this.count = count; - this.data = data; - - } - - /// packet xml order - public static mavlink_serial_control_t PopulateXMLOrder(/*SERIAL_CONTROL_DEV*/byte device,/*SERIAL_CONTROL_FLAG*/byte flags,ushort timeout,uint baudrate,byte count,byte[] data) - { - var msg = new mavlink_serial_control_t(); + /// Altitude above mean sea level [m] + [Units("[m]")] + [Description("Altitude above mean sea level")] + //[FieldOffset(14)] + public short altitude; - msg.device = device; - msg.flags = flags; - msg.timeout = timeout; - msg.baudrate = baudrate; - msg.count = count; - msg.data = data; - - return msg; - } - + /// Altitude setpoint [m] + [Units("[m]")] + [Description("Altitude setpoint")] + //[FieldOffset(16)] + public short target_altitude; - /// Baudrate of transfer. Zero means no change. [bits/s] - [Units("[bits/s]")] - [Description("Baudrate of transfer. Zero means no change.")] - //[FieldOffset(0)] - public uint baudrate; + /// Distance to target waypoint or position [dam] + [Units("[dam]")] + [Description("Distance to target waypoint or position")] + //[FieldOffset(18)] + public ushort target_distance; - /// Timeout for reply data [ms] - [Units("[ms]")] - [Description("Timeout for reply data")] - //[FieldOffset(4)] - public ushort timeout; + /// Current waypoint number + [Units("")] + [Description("Current waypoint number")] + //[FieldOffset(20)] + public ushort wp_num; - /// Serial control device type. SERIAL_CONTROL_DEV + /// Bitmap of failure flags. HL_FAILURE_FLAG bitmask [Units("")] - [Description("Serial control device type.")] - //[FieldOffset(6)] - public /*SERIAL_CONTROL_DEV*/byte device; + [Description("Bitmap of failure flags.")] + //[FieldOffset(22)] + public /*HL_FAILURE_FLAG*/ushort failure_flags; + + /// Type of the MAV (quadrotor, helicopter, etc.) MAV_TYPE + [Units("")] + [Description("Type of the MAV (quadrotor, helicopter, etc.)")] + //[FieldOffset(24)] + public /*MAV_TYPE*/byte type; + + /// Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. MAV_AUTOPILOT + [Units("")] + [Description("Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.")] + //[FieldOffset(25)] + public /*MAV_AUTOPILOT*/byte autopilot; + + /// Heading [deg/2] + [Units("[deg/2]")] + [Description("Heading")] + //[FieldOffset(26)] + public byte heading; + + /// Heading setpoint [deg/2] + [Units("[deg/2]")] + [Description("Heading setpoint")] + //[FieldOffset(27)] + public byte target_heading; + + /// Throttle [%] + [Units("[%]")] + [Description("Throttle")] + //[FieldOffset(28)] + public byte throttle; + + /// Airspeed [m/s*5] + [Units("[m/s*5]")] + [Description("Airspeed")] + //[FieldOffset(29)] + public byte airspeed; + + /// Airspeed setpoint [m/s*5] + [Units("[m/s*5]")] + [Description("Airspeed setpoint")] + //[FieldOffset(30)] + public byte airspeed_sp; + + /// Groundspeed [m/s*5] + [Units("[m/s*5]")] + [Description("Groundspeed")] + //[FieldOffset(31)] + public byte groundspeed; + + /// Windspeed [m/s*5] + [Units("[m/s*5]")] + [Description("Windspeed")] + //[FieldOffset(32)] + public byte windspeed; + + /// Wind heading [deg/2] + [Units("[deg/2]")] + [Description("Wind heading")] + //[FieldOffset(33)] + public byte wind_heading; + + /// Maximum error horizontal position since last message [dm] + [Units("[dm]")] + [Description("Maximum error horizontal position since last message")] + //[FieldOffset(34)] + public byte eph; + + /// Maximum error vertical position since last message [dm] + [Units("[dm]")] + [Description("Maximum error vertical position since last message")] + //[FieldOffset(35)] + public byte epv; + + /// Air temperature from airspeed sensor [degC] + [Units("[degC]")] + [Description("Air temperature from airspeed sensor")] + //[FieldOffset(36)] + public sbyte temperature_air; + + /// Maximum climb rate magnitude since last message [dm/s] + [Units("[dm/s]")] + [Description("Maximum climb rate magnitude since last message")] + //[FieldOffset(37)] + public sbyte climb_rate; + + /// Battery level (-1 if field not provided). [%] + [Units("[%]")] + [Description("Battery level (-1 if field not provided).")] + //[FieldOffset(38)] + public sbyte battery; - /// Bitmap of serial control flags. SERIAL_CONTROL_FLAG bitmask + /// Field for custom payload. [Units("")] - [Description("Bitmap of serial control flags.")] - //[FieldOffset(7)] - public /*SERIAL_CONTROL_FLAG*/byte flags; + [Description("Field for custom payload.")] + //[FieldOffset(39)] + public sbyte custom0; - /// how many bytes in this transfer [bytes] - [Units("[bytes]")] - [Description("how many bytes in this transfer")] - //[FieldOffset(8)] - public byte count; + /// Field for custom payload. + [Units("")] + [Description("Field for custom payload.")] + //[FieldOffset(40)] + public sbyte custom1; - /// serial data + /// Field for custom payload. [Units("")] - [Description("serial data")] - //[FieldOffset(9)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=70)] - public byte[] data; + [Description("Field for custom payload.")] + //[FieldOffset(41)] + public sbyte custom2; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] - /// RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - public struct mavlink_gps_rtk_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] + /// Vibration levels and accelerometer clipping + public struct mavlink_vibration_t { /// packet ordered constructor - public mavlink_gps_rtk_t(uint time_last_baseline_ms,uint tow,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses,ushort wn,byte rtk_receiver_id,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type) + public mavlink_vibration_t(ulong time_usec,float vibration_x,float vibration_y,float vibration_z,uint clipping_0,uint clipping_1,uint clipping_2) { - this.time_last_baseline_ms = time_last_baseline_ms; - this.tow = tow; - this.baseline_a_mm = baseline_a_mm; - this.baseline_b_mm = baseline_b_mm; - this.baseline_c_mm = baseline_c_mm; - this.accuracy = accuracy; - this.iar_num_hypotheses = iar_num_hypotheses; - this.wn = wn; - this.rtk_receiver_id = rtk_receiver_id; - this.rtk_health = rtk_health; - this.rtk_rate = rtk_rate; - this.nsats = nsats; - this.baseline_coords_type = baseline_coords_type; + this.time_usec = time_usec; + this.vibration_x = vibration_x; + this.vibration_y = vibration_y; + this.vibration_z = vibration_z; + this.clipping_0 = clipping_0; + this.clipping_1 = clipping_1; + this.clipping_2 = clipping_2; } /// packet xml order - public static mavlink_gps_rtk_t PopulateXMLOrder(uint time_last_baseline_ms,byte rtk_receiver_id,ushort wn,uint tow,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses) + public static mavlink_vibration_t PopulateXMLOrder(ulong time_usec,float vibration_x,float vibration_y,float vibration_z,uint clipping_0,uint clipping_1,uint clipping_2) { - var msg = new mavlink_gps_rtk_t(); + var msg = new mavlink_vibration_t(); - msg.time_last_baseline_ms = time_last_baseline_ms; - msg.rtk_receiver_id = rtk_receiver_id; - msg.wn = wn; - msg.tow = tow; - msg.rtk_health = rtk_health; - msg.rtk_rate = rtk_rate; - msg.nsats = nsats; - msg.baseline_coords_type = baseline_coords_type; - msg.baseline_a_mm = baseline_a_mm; - msg.baseline_b_mm = baseline_b_mm; - msg.baseline_c_mm = baseline_c_mm; - msg.accuracy = accuracy; - msg.iar_num_hypotheses = iar_num_hypotheses; + msg.time_usec = time_usec; + msg.vibration_x = vibration_x; + msg.vibration_y = vibration_y; + msg.vibration_z = vibration_z; + msg.clipping_0 = clipping_0; + msg.clipping_1 = clipping_1; + msg.clipping_2 = clipping_2; return msg; } - /// Time since boot of last baseline message received. [ms] - [Units("[ms]")] - [Description("Time since boot of last baseline message received.")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint time_last_baseline_ms; - - /// GPS Time of Week of last baseline [ms] - [Units("[ms]")] - [Description("GPS Time of Week of last baseline")] - //[FieldOffset(4)] - public uint tow; + public ulong time_usec; - /// Current baseline in ECEF x or NED north component. [mm] - [Units("[mm]")] - [Description("Current baseline in ECEF x or NED north component.")] + /// Vibration levels on X-axis + [Units("")] + [Description("Vibration levels on X-axis")] //[FieldOffset(8)] - public int baseline_a_mm; + public float vibration_x; - /// Current baseline in ECEF y or NED east component. [mm] - [Units("[mm]")] - [Description("Current baseline in ECEF y or NED east component.")] + /// Vibration levels on Y-axis + [Units("")] + [Description("Vibration levels on Y-axis")] //[FieldOffset(12)] - public int baseline_b_mm; + public float vibration_y; - /// Current baseline in ECEF z or NED down component. [mm] - [Units("[mm]")] - [Description("Current baseline in ECEF z or NED down component.")] + /// Vibration levels on Z-axis + [Units("")] + [Description("Vibration levels on Z-axis")] //[FieldOffset(16)] - public int baseline_c_mm; + public float vibration_z; - /// Current estimate of baseline accuracy. + /// first accelerometer clipping count [Units("")] - [Description("Current estimate of baseline accuracy.")] + [Description("first accelerometer clipping count")] //[FieldOffset(20)] - public uint accuracy; + public uint clipping_0; - /// Current number of integer ambiguity hypotheses. + /// second accelerometer clipping count [Units("")] - [Description("Current number of integer ambiguity hypotheses.")] + [Description("second accelerometer clipping count")] //[FieldOffset(24)] - public int iar_num_hypotheses; + public uint clipping_1; - /// GPS Week Number of last baseline + /// third accelerometer clipping count [Units("")] - [Description("GPS Week Number of last baseline")] + [Description("third accelerometer clipping count")] //[FieldOffset(28)] - public ushort wn; - - /// Identification of connected RTK receiver. - [Units("")] - [Description("Identification of connected RTK receiver.")] - //[FieldOffset(30)] - public byte rtk_receiver_id; - - /// GPS-specific health report for RTK data. - [Units("")] - [Description("GPS-specific health report for RTK data.")] - //[FieldOffset(31)] - public byte rtk_health; - - /// Rate of baseline messages being received by GPS [Hz] - [Units("[Hz]")] - [Description("Rate of baseline messages being received by GPS")] - //[FieldOffset(32)] - public byte rtk_rate; - - /// Current number of sats used for RTK calculation. - [Units("")] - [Description("Current number of sats used for RTK calculation.")] - //[FieldOffset(33)] - public byte nsats; - - /// Coordinate system of baseline RTK_BASELINE_COORDINATE_SYSTEM - [Units("")] - [Description("Coordinate system of baseline")] - //[FieldOffset(34)] - public /*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type; + public uint clipping_2; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] - /// RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - public struct mavlink_gps2_rtk_t + /// extensions_start 10 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=60)] + /// This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + public struct mavlink_home_position_t { /// packet ordered constructor - public mavlink_gps2_rtk_t(uint time_last_baseline_ms,uint tow,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses,ushort wn,byte rtk_receiver_id,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type) + public mavlink_home_position_t(int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,ulong time_usec) { - this.time_last_baseline_ms = time_last_baseline_ms; - this.tow = tow; - this.baseline_a_mm = baseline_a_mm; - this.baseline_b_mm = baseline_b_mm; - this.baseline_c_mm = baseline_c_mm; - this.accuracy = accuracy; - this.iar_num_hypotheses = iar_num_hypotheses; - this.wn = wn; - this.rtk_receiver_id = rtk_receiver_id; - this.rtk_health = rtk_health; - this.rtk_rate = rtk_rate; - this.nsats = nsats; - this.baseline_coords_type = baseline_coords_type; + this.latitude = latitude; + this.longitude = longitude; + this.altitude = altitude; + this.x = x; + this.y = y; + this.z = z; + this.q = q; + this.approach_x = approach_x; + this.approach_y = approach_y; + this.approach_z = approach_z; + this.time_usec = time_usec; } /// packet xml order - public static mavlink_gps2_rtk_t PopulateXMLOrder(uint time_last_baseline_ms,byte rtk_receiver_id,ushort wn,uint tow,byte rtk_health,byte rtk_rate,byte nsats,/*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type,int baseline_a_mm,int baseline_b_mm,int baseline_c_mm,uint accuracy,int iar_num_hypotheses) + public static mavlink_home_position_t PopulateXMLOrder(int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,ulong time_usec) { - var msg = new mavlink_gps2_rtk_t(); + var msg = new mavlink_home_position_t(); - msg.time_last_baseline_ms = time_last_baseline_ms; - msg.rtk_receiver_id = rtk_receiver_id; - msg.wn = wn; - msg.tow = tow; - msg.rtk_health = rtk_health; - msg.rtk_rate = rtk_rate; - msg.nsats = nsats; - msg.baseline_coords_type = baseline_coords_type; - msg.baseline_a_mm = baseline_a_mm; - msg.baseline_b_mm = baseline_b_mm; - msg.baseline_c_mm = baseline_c_mm; - msg.accuracy = accuracy; - msg.iar_num_hypotheses = iar_num_hypotheses; + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude = altitude; + msg.x = x; + msg.y = y; + msg.z = z; + msg.q = q; + msg.approach_x = approach_x; + msg.approach_y = approach_y; + msg.approach_z = approach_z; + msg.time_usec = time_usec; return msg; } - /// Time since boot of last baseline message received. [ms] - [Units("[ms]")] - [Description("Time since boot of last baseline message received.")] + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] //[FieldOffset(0)] - public uint time_last_baseline_ms; + public int latitude; - /// GPS Time of Week of last baseline [ms] - [Units("[ms]")] - [Description("GPS Time of Week of last baseline")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] //[FieldOffset(4)] - public uint tow; + public int longitude; - /// Current baseline in ECEF x or NED north component. [mm] + /// Altitude (MSL). Positive for up. [mm] [Units("[mm]")] - [Description("Current baseline in ECEF x or NED north component.")] + [Description("Altitude (MSL). Positive for up.")] //[FieldOffset(8)] - public int baseline_a_mm; + public int altitude; - /// Current baseline in ECEF y or NED east component. [mm] - [Units("[mm]")] - [Description("Current baseline in ECEF y or NED east component.")] + /// Local X position of this position in the local coordinate frame [m] + [Units("[m]")] + [Description("Local X position of this position in the local coordinate frame")] //[FieldOffset(12)] - public int baseline_b_mm; + public float x; - /// Current baseline in ECEF z or NED down component. [mm] - [Units("[mm]")] - [Description("Current baseline in ECEF z or NED down component.")] + /// Local Y position of this position in the local coordinate frame [m] + [Units("[m]")] + [Description("Local Y position of this position in the local coordinate frame")] //[FieldOffset(16)] - public int baseline_c_mm; + public float y; - /// Current estimate of baseline accuracy. - [Units("")] - [Description("Current estimate of baseline accuracy.")] + /// Local Z position of this position in the local coordinate frame [m] + [Units("[m]")] + [Description("Local Z position of this position in the local coordinate frame")] //[FieldOffset(20)] - public uint accuracy; + public float z; - /// Current number of integer ambiguity hypotheses. + /// World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground [Units("")] - [Description("Current number of integer ambiguity hypotheses.")] + [Description("World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground")] //[FieldOffset(24)] - public int iar_num_hypotheses; - - /// GPS Week Number of last baseline - [Units("")] - [Description("GPS Week Number of last baseline")] - //[FieldOffset(28)] - public ushort wn; - - /// Identification of connected RTK receiver. - [Units("")] - [Description("Identification of connected RTK receiver.")] - //[FieldOffset(30)] - public byte rtk_receiver_id; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// GPS-specific health report for RTK data. - [Units("")] - [Description("GPS-specific health report for RTK data.")] - //[FieldOffset(31)] - public byte rtk_health; + /// Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] + [Units("[m]")] + [Description("Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] + //[FieldOffset(40)] + public float approach_x; - /// Rate of baseline messages being received by GPS [Hz] - [Units("[Hz]")] - [Description("Rate of baseline messages being received by GPS")] - //[FieldOffset(32)] - public byte rtk_rate; + /// Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] + [Units("[m]")] + [Description("Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] + //[FieldOffset(44)] + public float approach_y; - /// Current number of sats used for RTK calculation. - [Units("")] - [Description("Current number of sats used for RTK calculation.")] - //[FieldOffset(33)] - public byte nsats; + /// Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] + [Units("[m]")] + [Description("Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] + //[FieldOffset(48)] + public float approach_z; - /// Coordinate system of baseline RTK_BASELINE_COORDINATE_SYSTEM - [Units("")] - [Description("Coordinate system of baseline")] - //[FieldOffset(34)] - public /*RTK_BASELINE_COORDINATE_SYSTEM*/byte baseline_coords_type; + /// 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. [us] + [Units("[us]")] + [Description("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.")] + //[FieldOffset(52)] + public ulong time_usec; }; - - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] - /// The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units - public struct mavlink_scaled_imu3_t + [Obsolete] + /// extensions_start 11 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=61)] + /// The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + public struct mavlink_set_home_position_t { /// packet ordered constructor - public mavlink_scaled_imu3_t(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) + public mavlink_set_home_position_t(int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,byte target_system,ulong time_usec) { - this.time_boot_ms = time_boot_ms; - this.xacc = xacc; - this.yacc = yacc; - this.zacc = zacc; - this.xgyro = xgyro; - this.ygyro = ygyro; - this.zgyro = zgyro; - this.xmag = xmag; - this.ymag = ymag; - this.zmag = zmag; - this.temperature = temperature; + this.latitude = latitude; + this.longitude = longitude; + this.altitude = altitude; + this.x = x; + this.y = y; + this.z = z; + this.q = q; + this.approach_x = approach_x; + this.approach_y = approach_y; + this.approach_z = approach_z; + this.target_system = target_system; + this.time_usec = time_usec; } /// packet xml order - public static mavlink_scaled_imu3_t PopulateXMLOrder(uint time_boot_ms,short xacc,short yacc,short zacc,short xgyro,short ygyro,short zgyro,short xmag,short ymag,short zmag,short temperature) + public static mavlink_set_home_position_t PopulateXMLOrder(byte target_system,int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,ulong time_usec) { - var msg = new mavlink_scaled_imu3_t(); + var msg = new mavlink_set_home_position_t(); - msg.time_boot_ms = time_boot_ms; - msg.xacc = xacc; - msg.yacc = yacc; - msg.zacc = zacc; - msg.xgyro = xgyro; - msg.ygyro = ygyro; - msg.zgyro = zgyro; - msg.xmag = xmag; - msg.ymag = ymag; - msg.zmag = zmag; - msg.temperature = temperature; + msg.target_system = target_system; + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude = altitude; + msg.x = x; + msg.y = y; + msg.z = z; + msg.q = q; + msg.approach_x = approach_x; + msg.approach_y = approach_y; + msg.approach_z = approach_z; + msg.time_usec = time_usec; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] //[FieldOffset(0)] - public uint time_boot_ms; + public int latitude; - /// X acceleration [mG] - [Units("[mG]")] - [Description("X acceleration")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] //[FieldOffset(4)] - public short xacc; - - /// Y acceleration [mG] - [Units("[mG]")] - [Description("Y acceleration")] - //[FieldOffset(6)] - public short yacc; + public int longitude; - /// Z acceleration [mG] - [Units("[mG]")] - [Description("Z acceleration")] + /// Altitude (MSL). Positive for up. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Positive for up.")] //[FieldOffset(8)] - public short zacc; - - /// Angular speed around X axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around X axis")] - //[FieldOffset(10)] - public short xgyro; + public int altitude; - /// Angular speed around Y axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around Y axis")] + /// Local X position of this position in the local coordinate frame [m] + [Units("[m]")] + [Description("Local X position of this position in the local coordinate frame")] //[FieldOffset(12)] - public short ygyro; - - /// Angular speed around Z axis [mrad/s] - [Units("[mrad/s]")] - [Description("Angular speed around Z axis")] - //[FieldOffset(14)] - public short zgyro; + public float x; - /// X Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("X Magnetic field")] + /// Local Y position of this position in the local coordinate frame [m] + [Units("[m]")] + [Description("Local Y position of this position in the local coordinate frame")] //[FieldOffset(16)] - public short xmag; - - /// Y Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("Y Magnetic field")] - //[FieldOffset(18)] - public short ymag; + public float y; - /// Z Magnetic field [mgauss] - [Units("[mgauss]")] - [Description("Z Magnetic field")] + /// Local Z position of this position in the local coordinate frame [m] + [Units("[m]")] + [Description("Local Z position of this position in the local coordinate frame")] //[FieldOffset(20)] - public short zmag; + public float z; - /// Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). [cdegC] - [Units("[cdegC]")] - [Description("Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).")] - //[FieldOffset(22)] - public short temperature; + /// World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + [Units("")] + [Description("World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; + + /// Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] + [Units("[m]")] + [Description("Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] + //[FieldOffset(40)] + public float approach_x; + + /// Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] + [Units("[m]")] + [Description("Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] + //[FieldOffset(44)] + public float approach_y; + + /// Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] + [Units("[m]")] + [Description("Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] + //[FieldOffset(48)] + public float approach_z; + + /// System ID. + [Units("")] + [Description("System ID.")] + //[FieldOffset(52)] + public byte target_system; + + /// 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. [us] + [Units("[us]")] + [Description("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.")] + //[FieldOffset(53)] + public ulong time_usec; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] - /// Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html. - public struct mavlink_data_transmission_handshake_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// The interval between messages for a particular MAVLink message ID. This message is the response to the MAV_CMD_GET_MESSAGE_INTERVAL command. This interface replaces DATA_STREAM. + public struct mavlink_message_interval_t { /// packet ordered constructor - public mavlink_data_transmission_handshake_t(uint size,ushort width,ushort height,ushort packets,/*MAVLINK_DATA_STREAM_TYPE*/byte type,byte payload,byte jpg_quality) + public mavlink_message_interval_t(int interval_us,ushort message_id) { - this.size = size; - this.width = width; - this.height = height; - this.packets = packets; - this.type = type; - this.payload = payload; - this.jpg_quality = jpg_quality; + this.interval_us = interval_us; + this.message_id = message_id; } /// packet xml order - public static mavlink_data_transmission_handshake_t PopulateXMLOrder(/*MAVLINK_DATA_STREAM_TYPE*/byte type,uint size,ushort width,ushort height,ushort packets,byte payload,byte jpg_quality) + public static mavlink_message_interval_t PopulateXMLOrder(ushort message_id,int interval_us) { - var msg = new mavlink_data_transmission_handshake_t(); + var msg = new mavlink_message_interval_t(); - msg.type = type; - msg.size = size; - msg.width = width; - msg.height = height; - msg.packets = packets; - msg.payload = payload; - msg.jpg_quality = jpg_quality; + msg.message_id = message_id; + msg.interval_us = interval_us; return msg; } - /// total data size (set on ACK only). [bytes] - [Units("[bytes]")] - [Description("total data size (set on ACK only).")] + /// The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. [us] + [Units("[us]")] + [Description("The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.")] //[FieldOffset(0)] - public uint size; + public int interval_us; - /// Width of a matrix or image. + /// The ID of the requested MAVLink message. v1.0 is limited to 254 messages. [Units("")] - [Description("Width of a matrix or image.")] + [Description("The ID of the requested MAVLink message. v1.0 is limited to 254 messages.")] //[FieldOffset(4)] - public ushort width; - - /// Height of a matrix or image. - [Units("")] - [Description("Height of a matrix or image.")] - //[FieldOffset(6)] - public ushort height; - - /// Number of packets being sent (set on ACK only). - [Units("")] - [Description("Number of packets being sent (set on ACK only).")] - //[FieldOffset(8)] - public ushort packets; - - /// Type of requested/acknowledged data. MAVLINK_DATA_STREAM_TYPE - [Units("")] - [Description("Type of requested/acknowledged data.")] - //[FieldOffset(10)] - public /*MAVLINK_DATA_STREAM_TYPE*/byte type; - - /// Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). [bytes] - [Units("[bytes]")] - [Description("Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).")] - //[FieldOffset(11)] - public byte payload; - - /// JPEG quality. Values: [1-100]. [%] - [Units("[%]")] - [Description("JPEG quality. Values: [1-100].")] - //[FieldOffset(12)] - public byte jpg_quality; + public ushort message_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] - /// Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html. - public struct mavlink_encapsulated_data_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Provides state for additional features + public struct mavlink_extended_sys_state_t { /// packet ordered constructor - public mavlink_encapsulated_data_t(ushort seqnr,byte[] data) + public mavlink_extended_sys_state_t(/*MAV_VTOL_STATE*/byte vtol_state,/*MAV_LANDED_STATE*/byte landed_state) { - this.seqnr = seqnr; - this.data = data; + this.vtol_state = vtol_state; + this.landed_state = landed_state; } /// packet xml order - public static mavlink_encapsulated_data_t PopulateXMLOrder(ushort seqnr,byte[] data) + public static mavlink_extended_sys_state_t PopulateXMLOrder(/*MAV_VTOL_STATE*/byte vtol_state,/*MAV_LANDED_STATE*/byte landed_state) { - var msg = new mavlink_encapsulated_data_t(); + var msg = new mavlink_extended_sys_state_t(); - msg.seqnr = seqnr; - msg.data = data; + msg.vtol_state = vtol_state; + msg.landed_state = landed_state; return msg; } - /// sequence number (starting with 0 on every transmission) + /// The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. MAV_VTOL_STATE [Units("")] - [Description("sequence number (starting with 0 on every transmission)")] + [Description("The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.")] //[FieldOffset(0)] - public ushort seqnr; + public /*MAV_VTOL_STATE*/byte vtol_state; - /// image data bytes + /// The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. MAV_LANDED_STATE [Units("")] - [Description("image data bytes")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=253)] - public byte[] data; + [Description("The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.")] + //[FieldOffset(1)] + public /*MAV_LANDED_STATE*/byte landed_state; }; - /// extensions_start 8 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=39)] - /// Distance sensor information for an onboard rangefinder. - public struct mavlink_distance_sensor_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] + /// The location and information of an ADSB vehicle + public struct mavlink_adsb_vehicle_t { /// packet ordered constructor - public mavlink_distance_sensor_t(uint time_boot_ms,ushort min_distance,ushort max_distance,ushort current_distance,/*MAV_DISTANCE_SENSOR*/byte type,byte id,/*MAV_SENSOR_ORIENTATION*/byte orientation,byte covariance,float horizontal_fov,float vertical_fov,float[] quaternion,byte signal_quality) + public mavlink_adsb_vehicle_t(uint ICAO_address,int lat,int lon,int altitude,ushort heading,ushort hor_velocity,short ver_velocity,/*ADSB_FLAGS*/ushort flags,ushort squawk,/*ADSB_ALTITUDE_TYPE*/byte altitude_type,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitter_type,byte tslc) { - this.time_boot_ms = time_boot_ms; - this.min_distance = min_distance; - this.max_distance = max_distance; - this.current_distance = current_distance; - this.type = type; - this.id = id; - this.orientation = orientation; - this.covariance = covariance; - this.horizontal_fov = horizontal_fov; - this.vertical_fov = vertical_fov; - this.quaternion = quaternion; - this.signal_quality = signal_quality; + this.ICAO_address = ICAO_address; + this.lat = lat; + this.lon = lon; + this.altitude = altitude; + this.heading = heading; + this.hor_velocity = hor_velocity; + this.ver_velocity = ver_velocity; + this.flags = flags; + this.squawk = squawk; + this.altitude_type = altitude_type; + this.callsign = callsign; + this.emitter_type = emitter_type; + this.tslc = tslc; } /// packet xml order - public static mavlink_distance_sensor_t PopulateXMLOrder(uint time_boot_ms,ushort min_distance,ushort max_distance,ushort current_distance,/*MAV_DISTANCE_SENSOR*/byte type,byte id,/*MAV_SENSOR_ORIENTATION*/byte orientation,byte covariance,float horizontal_fov,float vertical_fov,float[] quaternion,byte signal_quality) + public static mavlink_adsb_vehicle_t PopulateXMLOrder(uint ICAO_address,int lat,int lon,/*ADSB_ALTITUDE_TYPE*/byte altitude_type,int altitude,ushort heading,ushort hor_velocity,short ver_velocity,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitter_type,byte tslc,/*ADSB_FLAGS*/ushort flags,ushort squawk) { - var msg = new mavlink_distance_sensor_t(); + var msg = new mavlink_adsb_vehicle_t(); - msg.time_boot_ms = time_boot_ms; - msg.min_distance = min_distance; - msg.max_distance = max_distance; - msg.current_distance = current_distance; - msg.type = type; - msg.id = id; - msg.orientation = orientation; - msg.covariance = covariance; - msg.horizontal_fov = horizontal_fov; - msg.vertical_fov = vertical_fov; - msg.quaternion = quaternion; - msg.signal_quality = signal_quality; + msg.ICAO_address = ICAO_address; + msg.lat = lat; + msg.lon = lon; + msg.altitude_type = altitude_type; + msg.altitude = altitude; + msg.heading = heading; + msg.hor_velocity = hor_velocity; + msg.ver_velocity = ver_velocity; + msg.callsign = callsign; + msg.emitter_type = emitter_type; + msg.tslc = tslc; + msg.flags = flags; + msg.squawk = squawk; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// ICAO address + [Units("")] + [Description("ICAO address")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint ICAO_address; - /// Minimum distance the sensor can measure [cm] - [Units("[cm]")] - [Description("Minimum distance the sensor can measure")] + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] //[FieldOffset(4)] - public ushort min_distance; - - /// Maximum distance the sensor can measure [cm] - [Units("[cm]")] - [Description("Maximum distance the sensor can measure")] - //[FieldOffset(6)] - public ushort max_distance; + public int lat; - /// Current distance reading [cm] - [Units("[cm]")] - [Description("Current distance reading")] + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] //[FieldOffset(8)] - public ushort current_distance; + public int lon; - /// Type of distance sensor. MAV_DISTANCE_SENSOR - [Units("")] - [Description("Type of distance sensor.")] - //[FieldOffset(10)] - public /*MAV_DISTANCE_SENSOR*/byte type; + /// Altitude(ASL) [mm] + [Units("[mm]")] + [Description("Altitude(ASL)")] + //[FieldOffset(12)] + public int altitude; - /// Onboard ID of the sensor - [Units("")] - [Description("Onboard ID of the sensor")] - //[FieldOffset(11)] - public byte id; + /// Course over ground [cdeg] + [Units("[cdeg]")] + [Description("Course over ground")] + //[FieldOffset(16)] + public ushort heading; - /// Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 MAV_SENSOR_ORIENTATION + /// The horizontal velocity [cm/s] + [Units("[cm/s]")] + [Description("The horizontal velocity")] + //[FieldOffset(18)] + public ushort hor_velocity; + + /// The vertical velocity. Positive is up [cm/s] + [Units("[cm/s]")] + [Description("The vertical velocity. Positive is up")] + //[FieldOffset(20)] + public short ver_velocity; + + /// Bitmap to indicate various statuses including valid data fields ADSB_FLAGS bitmask [Units("")] - [Description("Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270")] - //[FieldOffset(12)] - public /*MAV_SENSOR_ORIENTATION*/byte orientation; + [Description("Bitmap to indicate various statuses including valid data fields")] + //[FieldOffset(22)] + public /*ADSB_FLAGS*/ushort flags; - /// Measurement variance. Max standard deviation is 6cm. 255 if unknown. [cm^2] - [Units("[cm^2]")] - [Description("Measurement variance. Max standard deviation is 6cm. 255 if unknown.")] - //[FieldOffset(13)] - public byte covariance; + /// Squawk code + [Units("")] + [Description("Squawk code")] + //[FieldOffset(24)] + public ushort squawk; - /// Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. [rad] - [Units("[rad]")] - [Description("Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.")] - //[FieldOffset(14)] - public float horizontal_fov; + /// ADSB altitude type. ADSB_ALTITUDE_TYPE + [Units("")] + [Description("ADSB altitude type.")] + //[FieldOffset(26)] + public /*ADSB_ALTITUDE_TYPE*/byte altitude_type; - /// Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. [rad] - [Units("[rad]")] - [Description("Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.")] - //[FieldOffset(18)] - public float vertical_fov; + /// The callsign, 8+null + [Units("")] + [Description("The callsign, 8+null")] + //[FieldOffset(27)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] + public byte[] callsign; - /// Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.' + /// ADSB emitter type. ADSB_EMITTER_TYPE [Units("")] - [Description("Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.'")] - //[FieldOffset(22)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] quaternion; + [Description("ADSB emitter type.")] + //[FieldOffset(36)] + public /*ADSB_EMITTER_TYPE*/byte emitter_type; - /// Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. [%] - [Units("[%]")] - [Description("Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.")] - //[FieldOffset(38)] - public byte signal_quality; + /// Time since last communication in seconds [s] + [Units("[s]")] + [Description("Time since last communication in seconds")] + //[FieldOffset(37)] + public byte tslc; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - /// Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html - public struct mavlink_terrain_request_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] + /// Information about a potential collision + public struct mavlink_collision_t { /// packet ordered constructor - public mavlink_terrain_request_t(ulong mask,int lat,int lon,ushort grid_spacing) + public mavlink_collision_t(uint id,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta,/*MAV_COLLISION_SRC*/byte src,/*MAV_COLLISION_ACTION*/byte action,/*MAV_COLLISION_THREAT_LEVEL*/byte threat_level) { - this.mask = mask; - this.lat = lat; - this.lon = lon; - this.grid_spacing = grid_spacing; + this.id = id; + this.time_to_minimum_delta = time_to_minimum_delta; + this.altitude_minimum_delta = altitude_minimum_delta; + this.horizontal_minimum_delta = horizontal_minimum_delta; + this.src = src; + this.action = action; + this.threat_level = threat_level; } /// packet xml order - public static mavlink_terrain_request_t PopulateXMLOrder(int lat,int lon,ushort grid_spacing,ulong mask) + public static mavlink_collision_t PopulateXMLOrder(/*MAV_COLLISION_SRC*/byte src,uint id,/*MAV_COLLISION_ACTION*/byte action,/*MAV_COLLISION_THREAT_LEVEL*/byte threat_level,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta) { - var msg = new mavlink_terrain_request_t(); + var msg = new mavlink_collision_t(); - msg.lat = lat; - msg.lon = lon; - msg.grid_spacing = grid_spacing; - msg.mask = mask; + msg.src = src; + msg.id = id; + msg.action = action; + msg.threat_level = threat_level; + msg.time_to_minimum_delta = time_to_minimum_delta; + msg.altitude_minimum_delta = altitude_minimum_delta; + msg.horizontal_minimum_delta = horizontal_minimum_delta; return msg; } - /// Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) bitmask + /// Unique identifier, domain based on src field [Units("")] - [Description("Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)")] + [Description("Unique identifier, domain based on src field")] //[FieldOffset(0)] - public ulong mask; + public uint id; - /// Latitude of SW corner of first grid [degE7] - [Units("[degE7]")] - [Description("Latitude of SW corner of first grid")] + /// Estimated time until collision occurs [s] + [Units("[s]")] + [Description("Estimated time until collision occurs")] + //[FieldOffset(4)] + public float time_to_minimum_delta; + + /// Closest vertical distance between vehicle and object [m] + [Units("[m]")] + [Description("Closest vertical distance between vehicle and object")] //[FieldOffset(8)] - public int lat; + public float altitude_minimum_delta; - /// Longitude of SW corner of first grid [degE7] - [Units("[degE7]")] - [Description("Longitude of SW corner of first grid")] + /// Closest horizontal distance between vehicle and object [m] + [Units("[m]")] + [Description("Closest horizontal distance between vehicle and object")] //[FieldOffset(12)] - public int lon; + public float horizontal_minimum_delta; - /// Grid spacing [m] - [Units("[m]")] - [Description("Grid spacing")] + /// Collision data source MAV_COLLISION_SRC + [Units("")] + [Description("Collision data source")] //[FieldOffset(16)] - public ushort grid_spacing; + public /*MAV_COLLISION_SRC*/byte src; + + /// Action that is being taken to avoid this collision MAV_COLLISION_ACTION + [Units("")] + [Description("Action that is being taken to avoid this collision")] + //[FieldOffset(17)] + public /*MAV_COLLISION_ACTION*/byte action; + + /// How concerned the aircraft is about this collision MAV_COLLISION_THREAT_LEVEL + [Units("")] + [Description("How concerned the aircraft is about this collision")] + //[FieldOffset(18)] + public /*MAV_COLLISION_THREAT_LEVEL*/byte threat_level; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=43)] - /// Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html - public struct mavlink_terrain_data_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=254)] + /// Message implementing parts of the V2 payload specs in V1 frames for transitional support. + public struct mavlink_v2_extension_t { /// packet ordered constructor - public mavlink_terrain_data_t(int lat,int lon,ushort grid_spacing,short[] data,byte gridbit) + public mavlink_v2_extension_t(ushort message_type,byte target_network,byte target_system,byte target_component,byte[] payload) { - this.lat = lat; - this.lon = lon; - this.grid_spacing = grid_spacing; - this.data = data; - this.gridbit = gridbit; + this.message_type = message_type; + this.target_network = target_network; + this.target_system = target_system; + this.target_component = target_component; + this.payload = payload; } /// packet xml order - public static mavlink_terrain_data_t PopulateXMLOrder(int lat,int lon,ushort grid_spacing,byte gridbit,short[] data) + public static mavlink_v2_extension_t PopulateXMLOrder(byte target_network,byte target_system,byte target_component,ushort message_type,byte[] payload) { - var msg = new mavlink_terrain_data_t(); + var msg = new mavlink_v2_extension_t(); - msg.lat = lat; - msg.lon = lon; - msg.grid_spacing = grid_spacing; - msg.gridbit = gridbit; - msg.data = data; + msg.target_network = target_network; + msg.target_system = target_system; + msg.target_component = target_component; + msg.message_type = message_type; + msg.payload = payload; return msg; } - /// Latitude of SW corner of first grid [degE7] - [Units("[degE7]")] - [Description("Latitude of SW corner of first grid")] + /// A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + [Units("")] + [Description("A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.")] //[FieldOffset(0)] - public int lat; + public ushort message_type; - /// Longitude of SW corner of first grid [degE7] - [Units("[degE7]")] - [Description("Longitude of SW corner of first grid")] - //[FieldOffset(4)] - public int lon; + /// Network ID (0 for broadcast) + [Units("")] + [Description("Network ID (0 for broadcast)")] + //[FieldOffset(2)] + public byte target_network; - /// Grid spacing [m] - [Units("[m]")] - [Description("Grid spacing")] - //[FieldOffset(8)] - public ushort grid_spacing; + /// System ID (0 for broadcast) + [Units("")] + [Description("System ID (0 for broadcast)")] + //[FieldOffset(3)] + public byte target_system; - /// Terrain data MSL [m] - [Units("[m]")] - [Description("Terrain data MSL")] - //[FieldOffset(10)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public short[] data; + /// Component ID (0 for broadcast) + [Units("")] + [Description("Component ID (0 for broadcast)")] + //[FieldOffset(4)] + public byte target_component; - /// bit within the terrain request mask + /// Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. [Units("")] - [Description("bit within the terrain request mask")] - //[FieldOffset(42)] - public byte gridbit; + [Description("Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification.")] + //[FieldOffset(5)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=249)] + public byte[] payload; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - /// Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission. - public struct mavlink_terrain_check_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)] + /// Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + public struct mavlink_memory_vect_t { /// packet ordered constructor - public mavlink_terrain_check_t(int lat,int lon) + public mavlink_memory_vect_t(ushort address,byte ver,byte type,sbyte[] value) { - this.lat = lat; - this.lon = lon; + this.address = address; + this.ver = ver; + this.type = type; + this.value = value; } /// packet xml order - public static mavlink_terrain_check_t PopulateXMLOrder(int lat,int lon) + public static mavlink_memory_vect_t PopulateXMLOrder(ushort address,byte ver,byte type,sbyte[] value) { - var msg = new mavlink_terrain_check_t(); + var msg = new mavlink_memory_vect_t(); - msg.lat = lat; - msg.lon = lon; + msg.address = address; + msg.ver = ver; + msg.type = type; + msg.value = value; return msg; } - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] + /// Starting address of the debug variables + [Units("")] + [Description("Starting address of the debug variables")] //[FieldOffset(0)] - public int lat; + public ushort address; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] + /// Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + [Units("")] + [Description("Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below")] + //[FieldOffset(2)] + public byte ver; + + /// Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + [Units("")] + [Description("Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14")] + //[FieldOffset(3)] + public byte type; + + /// Memory contents at specified address + [Units("")] + [Description("Memory contents at specified address")] //[FieldOffset(4)] - public int lon; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public sbyte[] value; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - /// Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html - public struct mavlink_terrain_report_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] + /// To debug something using a named 3D vector. + public struct mavlink_debug_vect_t { /// packet ordered constructor - public mavlink_terrain_report_t(int lat,int lon,float terrain_height,float current_height,ushort spacing,ushort pending,ushort loaded) + public mavlink_debug_vect_t(ulong time_usec,float x,float y,float z,byte[] name) { - this.lat = lat; - this.lon = lon; - this.terrain_height = terrain_height; - this.current_height = current_height; - this.spacing = spacing; - this.pending = pending; - this.loaded = loaded; + this.time_usec = time_usec; + this.x = x; + this.y = y; + this.z = z; + this.name = name; } /// packet xml order - public static mavlink_terrain_report_t PopulateXMLOrder(int lat,int lon,ushort spacing,float terrain_height,float current_height,ushort pending,ushort loaded) + public static mavlink_debug_vect_t PopulateXMLOrder(byte[] name,ulong time_usec,float x,float y,float z) { - var msg = new mavlink_terrain_report_t(); + var msg = new mavlink_debug_vect_t(); - msg.lat = lat; - msg.lon = lon; - msg.spacing = spacing; - msg.terrain_height = terrain_height; - msg.current_height = current_height; - msg.pending = pending; - msg.loaded = loaded; + msg.name = name; + msg.time_usec = time_usec; + msg.x = x; + msg.y = y; + msg.z = z; return msg; } - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public int lat; - - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] - //[FieldOffset(4)] - public int lon; + public ulong time_usec; - /// Terrain height MSL [m] - [Units("[m]")] - [Description("Terrain height MSL")] + /// x + [Units("")] + [Description("x")] //[FieldOffset(8)] - public float terrain_height; + public float x; - /// Current vehicle height above lat/lon terrain height [m] - [Units("[m]")] - [Description("Current vehicle height above lat/lon terrain height")] + /// y + [Units("")] + [Description("y")] //[FieldOffset(12)] - public float current_height; + public float y; - /// grid spacing (zero if terrain at this location unavailable) + /// z [Units("")] - [Description("grid spacing (zero if terrain at this location unavailable)")] + [Description("z")] //[FieldOffset(16)] - public ushort spacing; - - /// Number of 4x4 terrain blocks waiting to be received or read from disk - [Units("")] - [Description("Number of 4x4 terrain blocks waiting to be received or read from disk")] - //[FieldOffset(18)] - public ushort pending; + public float z; - /// Number of 4x4 terrain blocks in memory + /// Name [Units("")] - [Description("Number of 4x4 terrain blocks in memory")] + [Description("Name")] //[FieldOffset(20)] - public ushort loaded; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public byte[] name; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// Barometer readings for 2nd barometer - public struct mavlink_scaled_pressure2_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] + /// Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + public struct mavlink_named_value_float_t { /// packet ordered constructor - public mavlink_scaled_pressure2_t(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) + public mavlink_named_value_float_t(uint time_boot_ms,float value,byte[] name) { this.time_boot_ms = time_boot_ms; - this.press_abs = press_abs; - this.press_diff = press_diff; - this.temperature = temperature; - this.temperature_press_diff = temperature_press_diff; + this.value = value; + this.name = name; } /// packet xml order - public static mavlink_scaled_pressure2_t PopulateXMLOrder(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) + public static mavlink_named_value_float_t PopulateXMLOrder(uint time_boot_ms,byte[] name,float value) { - var msg = new mavlink_scaled_pressure2_t(); + var msg = new mavlink_named_value_float_t(); msg.time_boot_ms = time_boot_ms; - msg.press_abs = press_abs; - msg.press_diff = press_diff; - msg.temperature = temperature; - msg.temperature_press_diff = temperature_press_diff; + msg.name = name; + msg.value = value; return msg; } @@ -21763,387 +27711,376 @@ public static mavlink_scaled_pressure2_t PopulateXMLOrder(uint time_boot_ms,floa //[FieldOffset(0)] public uint time_boot_ms; - /// Absolute pressure [hPa] - [Units("[hPa]")] - [Description("Absolute pressure")] + /// Floating point value + [Units("")] + [Description("Floating point value")] //[FieldOffset(4)] - public float press_abs; + public float value; - /// Differential pressure [hPa] - [Units("[hPa]")] - [Description("Differential pressure")] + /// Name of the debug variable + [Units("")] + [Description("Name of the debug variable")] //[FieldOffset(8)] - public float press_diff; - - /// Absolute pressure temperature [cdegC] - [Units("[cdegC]")] - [Description("Absolute pressure temperature")] - //[FieldOffset(12)] - public short temperature; - - /// Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. [cdegC] - [Units("[cdegC]")] - [Description("Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.")] - //[FieldOffset(14)] - public short temperature_press_diff; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public byte[] name; }; - /// extensions_start 5 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=120)] - /// Motion capture attitude and position - public struct mavlink_att_pos_mocap_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] + /// Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + public struct mavlink_named_value_int_t { /// packet ordered constructor - public mavlink_att_pos_mocap_t(ulong time_usec,float[] q,float x,float y,float z,float[] covariance) + public mavlink_named_value_int_t(uint time_boot_ms,int value,byte[] name) { - this.time_usec = time_usec; - this.q = q; - this.x = x; - this.y = y; - this.z = z; - this.covariance = covariance; + this.time_boot_ms = time_boot_ms; + this.value = value; + this.name = name; } /// packet xml order - public static mavlink_att_pos_mocap_t PopulateXMLOrder(ulong time_usec,float[] q,float x,float y,float z,float[] covariance) + public static mavlink_named_value_int_t PopulateXMLOrder(uint time_boot_ms,byte[] name,int value) { - var msg = new mavlink_att_pos_mocap_t(); + var msg = new mavlink_named_value_int_t(); - msg.time_usec = time_usec; - msg.q = q; - msg.x = x; - msg.y = y; - msg.z = z; - msg.covariance = covariance; + msg.time_boot_ms = time_boot_ms; + msg.name = name; + msg.value = value; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + /// Signed integer value [Units("")] - [Description("Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// X position (NED) [m] - [Units("[m]")] - [Description("X position (NED)")] - //[FieldOffset(24)] - public float x; - - /// Y position (NED) [m] - [Units("[m]")] - [Description("Y position (NED)")] - //[FieldOffset(28)] - public float y; - - /// Z position (NED) [m] - [Units("[m]")] - [Description("Z position (NED)")] - //[FieldOffset(32)] - public float z; + [Description("Signed integer value")] + //[FieldOffset(4)] + public int value; - /// Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. + /// Name of the debug variable [Units("")] - [Description("Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(36)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] - public float[] covariance; + [Description("Name of the debug variable")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public byte[] name; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=43)] - /// Set the vehicle attitude and body angular rates. - public struct mavlink_set_actuator_control_target_t + /// extensions_start 2 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] + /// Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + public struct mavlink_statustext_t { /// packet ordered constructor - public mavlink_set_actuator_control_target_t(ulong time_usec,float[] controls,byte group_mlx,byte target_system,byte target_component) + public mavlink_statustext_t(/*MAV_SEVERITY*/byte severity,byte[] text,ushort id,byte chunk_seq) { - this.time_usec = time_usec; - this.controls = controls; - this.group_mlx = group_mlx; - this.target_system = target_system; - this.target_component = target_component; + this.severity = severity; + this.text = text; + this.id = id; + this.chunk_seq = chunk_seq; } /// packet xml order - public static mavlink_set_actuator_control_target_t PopulateXMLOrder(ulong time_usec,byte group_mlx,byte target_system,byte target_component,float[] controls) + public static mavlink_statustext_t PopulateXMLOrder(/*MAV_SEVERITY*/byte severity,byte[] text,ushort id,byte chunk_seq) { - var msg = new mavlink_set_actuator_control_target_t(); + var msg = new mavlink_statustext_t(); - msg.time_usec = time_usec; - msg.group_mlx = group_mlx; - msg.target_system = target_system; - msg.target_component = target_component; - msg.controls = controls; + msg.severity = severity; + msg.text = text; + msg.id = id; + msg.chunk_seq = chunk_seq; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(0)] - public ulong time_usec; - - /// Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + /// Severity of status. Relies on the definitions within RFC-5424. MAV_SEVERITY [Units("")] - [Description("Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public float[] controls; + [Description("Severity of status. Relies on the definitions within RFC-5424.")] + //[FieldOffset(0)] + public /*MAV_SEVERITY*/byte severity; - /// Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + /// Status text message, without null termination character [Units("")] - [Description("Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.")] - //[FieldOffset(40)] - public byte group_mlx; + [Description("Status text message, without null termination character")] + //[FieldOffset(1)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] text; - /// System ID + /// Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. [Units("")] - [Description("System ID")] - //[FieldOffset(41)] - public byte target_system; + [Description("Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.")] + //[FieldOffset(51)] + public ushort id; - /// Component ID + /// This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. [Units("")] - [Description("Component ID")] - //[FieldOffset(42)] - public byte target_component; + [Description("This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.")] + //[FieldOffset(53)] + public byte chunk_seq; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=41)] - /// Set the vehicle attitude and body angular rates. - public struct mavlink_actuator_control_target_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + public struct mavlink_debug_t { /// packet ordered constructor - public mavlink_actuator_control_target_t(ulong time_usec,float[] controls,byte group_mlx) + public mavlink_debug_t(uint time_boot_ms,float value,byte ind) { - this.time_usec = time_usec; - this.controls = controls; - this.group_mlx = group_mlx; + this.time_boot_ms = time_boot_ms; + this.value = value; + this.ind = ind; } /// packet xml order - public static mavlink_actuator_control_target_t PopulateXMLOrder(ulong time_usec,byte group_mlx,float[] controls) + public static mavlink_debug_t PopulateXMLOrder(uint time_boot_ms,byte ind,float value) { - var msg = new mavlink_actuator_control_target_t(); + var msg = new mavlink_debug_t(); - msg.time_usec = time_usec; - msg.group_mlx = group_mlx; - msg.controls = controls; + msg.time_boot_ms = time_boot_ms; + msg.ind = ind; + msg.value = value; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + /// DEBUG value [Units("")] - [Description("Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public float[] controls; + [Description("DEBUG value")] + //[FieldOffset(4)] + public float value; - /// Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + /// index of debug variable [Units("")] - [Description("Actuator group. The '_mlx' indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.")] - //[FieldOffset(40)] - public byte group_mlx; + [Description("index of debug variable")] + //[FieldOffset(8)] + public byte ind; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - /// The current system altitude. - public struct mavlink_altitude_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing + public struct mavlink_setup_signing_t { /// packet ordered constructor - public mavlink_altitude_t(ulong time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) + public mavlink_setup_signing_t(ulong initial_timestamp,byte target_system,byte target_component,byte[] secret_key) { - this.time_usec = time_usec; - this.altitude_monotonic = altitude_monotonic; - this.altitude_amsl = altitude_amsl; - this.altitude_local = altitude_local; - this.altitude_relative = altitude_relative; - this.altitude_terrain = altitude_terrain; - this.bottom_clearance = bottom_clearance; + this.initial_timestamp = initial_timestamp; + this.target_system = target_system; + this.target_component = target_component; + this.secret_key = secret_key; } /// packet xml order - public static mavlink_altitude_t PopulateXMLOrder(ulong time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) + public static mavlink_setup_signing_t PopulateXMLOrder(byte target_system,byte target_component,byte[] secret_key,ulong initial_timestamp) { - var msg = new mavlink_altitude_t(); + var msg = new mavlink_setup_signing_t(); - msg.time_usec = time_usec; - msg.altitude_monotonic = altitude_monotonic; - msg.altitude_amsl = altitude_amsl; - msg.altitude_local = altitude_local; - msg.altitude_relative = altitude_relative; - msg.altitude_terrain = altitude_terrain; - msg.bottom_clearance = bottom_clearance; + msg.target_system = target_system; + msg.target_component = target_component; + msg.secret_key = secret_key; + msg.initial_timestamp = initial_timestamp; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// initial timestamp + [Units("")] + [Description("initial timestamp")] //[FieldOffset(0)] - public ulong time_usec; + public ulong initial_timestamp; - /// This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. [m] - [Units("[m]")] - [Description("This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.")] + /// system id of the target + [Units("")] + [Description("system id of the target")] //[FieldOffset(8)] - public float altitude_monotonic; + public byte target_system; - /// This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. [m] - [Units("[m]")] - [Description("This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.")] - //[FieldOffset(12)] - public float altitude_amsl; + /// component ID of the target + [Units("")] + [Description("component ID of the target")] + //[FieldOffset(9)] + public byte target_component; - /// This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. [m] - [Units("[m]")] - [Description("This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.")] - //[FieldOffset(16)] - public float altitude_local; + /// signing key + [Units("")] + [Description("signing key")] + //[FieldOffset(10)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] secret_key; + }; - /// This is the altitude above the home position. It resets on each change of the current home position. [m] - [Units("[m]")] - [Description("This is the altitude above the home position. It resets on each change of the current home position.")] - //[FieldOffset(20)] - public float altitude_relative; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Report button state change. + public struct mavlink_button_change_t + { + /// packet ordered constructor + public mavlink_button_change_t(uint time_boot_ms,uint last_change_ms,byte state) + { + this.time_boot_ms = time_boot_ms; + this.last_change_ms = last_change_ms; + this.state = state; + + } + + /// packet xml order + public static mavlink_button_change_t PopulateXMLOrder(uint time_boot_ms,uint last_change_ms,byte state) + { + var msg = new mavlink_button_change_t(); - /// This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. [m] - [Units("[m]")] - [Description("This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.")] - //[FieldOffset(24)] - public float altitude_terrain; + msg.time_boot_ms = time_boot_ms; + msg.last_change_ms = last_change_ms; + msg.state = state; + + return msg; + } + - /// This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. [m] - [Units("[m]")] - [Description("This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.")] - //[FieldOffset(28)] - public float bottom_clearance; + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; + + /// Time of last change of button state. [ms] + [Units("[ms]")] + [Description("Time of last change of button state.")] + //[FieldOffset(4)] + public uint last_change_ms; + + /// Bitmap for state of buttons. bitmask + [Units("")] + [Description("Bitmap for state of buttons.")] + //[FieldOffset(8)] + public byte state; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=243)] - /// The autopilot is requesting a resource (file, binary, other type of data) - public struct mavlink_resource_request_t + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=232)] + /// Control vehicle tone generation (buzzer). + public struct mavlink_play_tune_t { /// packet ordered constructor - public mavlink_resource_request_t(byte request_id,byte uri_type,byte[] uri,byte transfer_type,byte[] storage) + public mavlink_play_tune_t(byte target_system,byte target_component,byte[] tune,byte[] tune2) { - this.request_id = request_id; - this.uri_type = uri_type; - this.uri = uri; - this.transfer_type = transfer_type; - this.storage = storage; + this.target_system = target_system; + this.target_component = target_component; + this.tune = tune; + this.tune2 = tune2; } /// packet xml order - public static mavlink_resource_request_t PopulateXMLOrder(byte request_id,byte uri_type,byte[] uri,byte transfer_type,byte[] storage) + public static mavlink_play_tune_t PopulateXMLOrder(byte target_system,byte target_component,byte[] tune,byte[] tune2) { - var msg = new mavlink_resource_request_t(); + var msg = new mavlink_play_tune_t(); - msg.request_id = request_id; - msg.uri_type = uri_type; - msg.uri = uri; - msg.transfer_type = transfer_type; - msg.storage = storage; + msg.target_system = target_system; + msg.target_component = target_component; + msg.tune = tune; + msg.tune2 = tune2; return msg; } - /// Request ID. This ID should be re-used when sending back URI contents + /// System ID [Units("")] - [Description("Request ID. This ID should be re-used when sending back URI contents")] + [Description("System ID")] //[FieldOffset(0)] - public byte request_id; + public byte target_system; - /// The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + /// Component ID [Units("")] - [Description("The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary")] + [Description("Component ID")] //[FieldOffset(1)] - public byte uri_type; - - /// The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - [Units("")] - [Description("The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=120)] - public byte[] uri; + public byte target_component; - /// The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + /// tune in board specific format [Units("")] - [Description("The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.")] - //[FieldOffset(122)] - public byte transfer_type; + [Description("tune in board specific format")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=30)] + public byte[] tune; - /// The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + /// tune extension (appended to tune) [Units("")] - [Description("The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).")] - //[FieldOffset(123)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=120)] - public byte[] storage; + [Description("tune extension (appended to tune)")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=200)] + public byte[] tune2; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// Barometer readings for 3rd barometer - public struct mavlink_scaled_pressure3_t + /// 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_scaled_pressure3_t(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) + 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.press_abs = press_abs; - this.press_diff = press_diff; - this.temperature = temperature; - this.temperature_press_diff = temperature_press_diff; + this.firmware_version = firmware_version; + this.focal_length = focal_length; + this.sensor_size_h = sensor_size_h; + this.sensor_size_v = sensor_size_v; + this.flags = flags; + this.resolution_h = resolution_h; + this.resolution_v = resolution_v; + this.cam_definition_version = cam_definition_version; + this.vendor_name = vendor_name; + 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_scaled_pressure3_t PopulateXMLOrder(uint time_boot_ms,float press_abs,float press_diff,short temperature,short temperature_press_diff) + 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_scaled_pressure3_t(); + var msg = new mavlink_camera_information_t(); msg.time_boot_ms = time_boot_ms; - msg.press_abs = press_abs; - msg.press_diff = press_diff; - msg.temperature = temperature; - msg.temperature_press_diff = temperature_press_diff; + msg.vendor_name = vendor_name; + msg.model_name = model_name; + msg.firmware_version = firmware_version; + msg.focal_length = focal_length; + msg.sensor_size_h = sensor_size_h; + msg.sensor_size_v = sensor_size_v; + msg.resolution_h = resolution_h; + msg.resolution_v = resolution_v; + msg.lens_id = lens_id; + 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; } @@ -22155,70 +28092,113 @@ public static mavlink_scaled_pressure3_t PopulateXMLOrder(uint time_boot_ms,floa //[FieldOffset(0)] public uint time_boot_ms; - /// Absolute pressure [hPa] - [Units("[hPa]")] - [Description("Absolute pressure")] + /// Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. + [Units("")] + [Description("Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.")] //[FieldOffset(4)] - public float press_abs; + public uint firmware_version; - /// Differential pressure [hPa] - [Units("[hPa]")] - [Description("Differential pressure")] + /// Focal length. Use NaN if not known. [mm] + [Units("[mm]")] + [Description("Focal length. Use NaN if not known.")] //[FieldOffset(8)] - public float press_diff; + public float focal_length; - /// Absolute pressure temperature [cdegC] - [Units("[cdegC]")] - [Description("Absolute pressure temperature")] + /// Image sensor size horizontal. Use NaN if not known. [mm] + [Units("[mm]")] + [Description("Image sensor size horizontal. Use NaN if not known.")] //[FieldOffset(12)] - public short temperature; + public float sensor_size_h; - /// Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. [cdegC] - [Units("[cdegC]")] - [Description("Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.")] - //[FieldOffset(14)] - public short temperature_press_diff; + /// Image sensor size vertical. Use NaN if not known. [mm] + [Units("[mm]")] + [Description("Image sensor size vertical. Use NaN if not known.")] + //[FieldOffset(16)] + public float sensor_size_v; + + /// Bitmap of camera capability flags. CAMERA_CAP_FLAGS bitmask + [Units("")] + [Description("Bitmap of camera capability flags.")] + //[FieldOffset(20)] + public /*CAMERA_CAP_FLAGS*/uint flags; + + /// Horizontal image resolution. Use 0 if not known. [pix] + [Units("[pix]")] + [Description("Horizontal image resolution. Use 0 if not known.")] + //[FieldOffset(24)] + public ushort resolution_h; + + /// Vertical image resolution. Use 0 if not known. [pix] + [Units("[pix]")] + [Description("Vertical image resolution. Use 0 if not known.")] + //[FieldOffset(26)] + public ushort resolution_v; + + /// Camera definition version (iteration). Use 0 if not known. + [Units("")] + [Description("Camera definition version (iteration). Use 0 if not known.")] + //[FieldOffset(28)] + public ushort cam_definition_version; + + /// Name of the camera vendor + [Units("")] + [Description("Name of the camera vendor")] + //[FieldOffset(30)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] vendor_name; + + /// Name of the camera model + [Units("")] + [Description("Name of the camera model")] + //[FieldOffset(62)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] model_name; + + /// Reserved for a lens ID. Use 0 if not known. + [Units("")] + [Description("Reserved for a lens ID. Use 0 if not known.")] + //[FieldOffset(94)] + public byte lens_id; + + /// 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. + [Units("")] + [Description("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.")] + //[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; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=93)] - /// Current motion information from a designated system - public struct mavlink_follow_target_t + /// extensions_start 2 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] + /// Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. + public struct mavlink_camera_settings_t { /// packet ordered constructor - public mavlink_follow_target_t(ulong timestamp,ulong custom_state,int lat,int lon,float alt,float[] vel,float[] acc,float[] attitude_q,float[] rates,float[] position_cov,byte est_capabilities) + public mavlink_camera_settings_t(uint time_boot_ms,/*CAMERA_MODE*/byte mode_id,float zoomLevel,float focusLevel) { - this.timestamp = timestamp; - this.custom_state = custom_state; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.vel = vel; - this.acc = acc; - this.attitude_q = attitude_q; - this.rates = rates; - this.position_cov = position_cov; - this.est_capabilities = est_capabilities; + this.time_boot_ms = time_boot_ms; + this.mode_id = mode_id; + this.zoomLevel = zoomLevel; + this.focusLevel = focusLevel; } /// packet xml order - public static mavlink_follow_target_t PopulateXMLOrder(ulong timestamp,byte est_capabilities,int lat,int lon,float alt,float[] vel,float[] acc,float[] attitude_q,float[] rates,float[] position_cov,ulong custom_state) + public static mavlink_camera_settings_t PopulateXMLOrder(uint time_boot_ms,/*CAMERA_MODE*/byte mode_id,float zoomLevel,float focusLevel) { - var msg = new mavlink_follow_target_t(); + var msg = new mavlink_camera_settings_t(); - msg.timestamp = timestamp; - msg.est_capabilities = est_capabilities; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.vel = vel; - msg.acc = acc; - msg.attitude_q = attitude_q; - msg.rates = rates; - msg.position_cov = position_cov; - msg.custom_state = custom_state; + msg.time_boot_ms = time_boot_ms; + msg.mode_id = mode_id; + msg.zoomLevel = zoomLevel; + msg.focusLevel = focusLevel; return msg; } @@ -22228,3019 +28208,2650 @@ public static mavlink_follow_target_t PopulateXMLOrder(ulong timestamp,byte est_ [Units("[ms]")] [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong timestamp; - - /// button states or switches of a tracker device - [Units("")] - [Description("button states or switches of a tracker device")] - //[FieldOffset(8)] - public ulong custom_state; - - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] - //[FieldOffset(16)] - public int lat; - - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] - //[FieldOffset(20)] - public int lon; - - /// Altitude (MSL) [m] - [Units("[m]")] - [Description("Altitude (MSL)")] - //[FieldOffset(24)] - public float alt; - - /// target velocity (0,0,0) for unknown [m/s] - [Units("[m/s]")] - [Description("target velocity (0,0,0) for unknown")] - //[FieldOffset(28)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] vel; - - /// linear target acceleration (0,0,0) for unknown [m/s/s] - [Units("[m/s/s]")] - [Description("linear target acceleration (0,0,0) for unknown")] - //[FieldOffset(40)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] acc; - - /// (1 0 0 0 for unknown) - [Units("")] - [Description("(1 0 0 0 for unknown)")] - //[FieldOffset(52)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] attitude_q; + public uint time_boot_ms; - /// (0 0 0 for unknown) + /// Camera mode CAMERA_MODE [Units("")] - [Description("(0 0 0 for unknown)")] - //[FieldOffset(68)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] rates; + [Description("Camera mode")] + //[FieldOffset(4)] + public /*CAMERA_MODE*/byte mode_id; - /// eph epv + /// Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) [Units("")] - [Description("eph epv")] - //[FieldOffset(80)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] position_cov; + [Description("Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)")] + //[FieldOffset(5)] + public float zoomLevel; - /// bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + /// Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) [Units("")] - [Description("bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)")] - //[FieldOffset(92)] - public byte est_capabilities; + [Description("Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)")] + //[FieldOffset(9)] + public float focusLevel; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=100)] - /// The smoothed, monotonic system state used to feed the control loops of the system. - public struct mavlink_control_system_state_t + /// extensions_start 9 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=60)] + /// Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc. + public struct mavlink_storage_information_t { /// packet ordered constructor - public mavlink_control_system_state_t(ulong time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,float[] vel_variance,float[] pos_variance,float[] q,float roll_rate,float pitch_rate,float yaw_rate) + public mavlink_storage_information_t(uint time_boot_ms,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed,byte storage_id,byte storage_count,/*STORAGE_STATUS*/byte status,/*STORAGE_TYPE*/byte type,byte[] name) { - this.time_usec = time_usec; - this.x_acc = x_acc; - this.y_acc = y_acc; - this.z_acc = z_acc; - this.x_vel = x_vel; - this.y_vel = y_vel; - this.z_vel = z_vel; - this.x_pos = x_pos; - this.y_pos = y_pos; - this.z_pos = z_pos; - this.airspeed = airspeed; - this.vel_variance = vel_variance; - this.pos_variance = pos_variance; - this.q = q; - this.roll_rate = roll_rate; - this.pitch_rate = pitch_rate; - this.yaw_rate = yaw_rate; + this.time_boot_ms = time_boot_ms; + this.total_capacity = total_capacity; + this.used_capacity = used_capacity; + this.available_capacity = available_capacity; + this.read_speed = read_speed; + this.write_speed = write_speed; + this.storage_id = storage_id; + this.storage_count = storage_count; + this.status = status; + this.type = type; + this.name = name; } /// packet xml order - public static mavlink_control_system_state_t PopulateXMLOrder(ulong time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,float[] vel_variance,float[] pos_variance,float[] q,float roll_rate,float pitch_rate,float yaw_rate) + public static mavlink_storage_information_t PopulateXMLOrder(uint time_boot_ms,byte storage_id,byte storage_count,/*STORAGE_STATUS*/byte status,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed,/*STORAGE_TYPE*/byte type,byte[] name) { - var msg = new mavlink_control_system_state_t(); + var msg = new mavlink_storage_information_t(); - msg.time_usec = time_usec; - msg.x_acc = x_acc; - msg.y_acc = y_acc; - msg.z_acc = z_acc; - msg.x_vel = x_vel; - msg.y_vel = y_vel; - msg.z_vel = z_vel; - msg.x_pos = x_pos; - msg.y_pos = y_pos; - msg.z_pos = z_pos; - msg.airspeed = airspeed; - msg.vel_variance = vel_variance; - msg.pos_variance = pos_variance; - msg.q = q; - msg.roll_rate = roll_rate; - msg.pitch_rate = pitch_rate; - msg.yaw_rate = yaw_rate; + msg.time_boot_ms = time_boot_ms; + msg.storage_id = storage_id; + msg.storage_count = storage_count; + msg.status = status; + msg.total_capacity = total_capacity; + msg.used_capacity = used_capacity; + msg.available_capacity = available_capacity; + msg.read_speed = read_speed; + msg.write_speed = write_speed; + msg.type = type; + msg.name = name; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// X acceleration in body frame [m/s/s] - [Units("[m/s/s]")] - [Description("X acceleration in body frame")] + /// Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. [MiB] + [Units("[MiB]")] + [Description("Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.")] + //[FieldOffset(4)] + public float total_capacity; + + /// Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. [MiB] + [Units("[MiB]")] + [Description("Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.")] //[FieldOffset(8)] - public float x_acc; + public float used_capacity; - /// Y acceleration in body frame [m/s/s] - [Units("[m/s/s]")] - [Description("Y acceleration in body frame")] + /// Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. [MiB] + [Units("[MiB]")] + [Description("Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.")] //[FieldOffset(12)] - public float y_acc; + public float available_capacity; - /// Z acceleration in body frame [m/s/s] - [Units("[m/s/s]")] - [Description("Z acceleration in body frame")] + /// Read speed. [MiB/s] + [Units("[MiB/s]")] + [Description("Read speed.")] //[FieldOffset(16)] - public float z_acc; + public float read_speed; - /// X velocity in body frame [m/s] - [Units("[m/s]")] - [Description("X velocity in body frame")] + /// Write speed. [MiB/s] + [Units("[MiB/s]")] + [Description("Write speed.")] //[FieldOffset(20)] - public float x_vel; + public float write_speed; - /// Y velocity in body frame [m/s] - [Units("[m/s]")] - [Description("Y velocity in body frame")] + /// Storage ID (1 for first, 2 for second, etc.) + [Units("")] + [Description("Storage ID (1 for first, 2 for second, etc.)")] //[FieldOffset(24)] - public float y_vel; - - /// Z velocity in body frame [m/s] - [Units("[m/s]")] - [Description("Z velocity in body frame")] - //[FieldOffset(28)] - public float z_vel; - - /// X position in local frame [m] - [Units("[m]")] - [Description("X position in local frame")] - //[FieldOffset(32)] - public float x_pos; - - /// Y position in local frame [m] - [Units("[m]")] - [Description("Y position in local frame")] - //[FieldOffset(36)] - public float y_pos; - - /// Z position in local frame [m] - [Units("[m]")] - [Description("Z position in local frame")] - //[FieldOffset(40)] - public float z_pos; - - /// Airspeed, set to -1 if unknown [m/s] - [Units("[m/s]")] - [Description("Airspeed, set to -1 if unknown")] - //[FieldOffset(44)] - public float airspeed; + public byte storage_id; - /// Variance of body velocity estimate + /// Number of storage devices [Units("")] - [Description("Variance of body velocity estimate")] - //[FieldOffset(48)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] vel_variance; + [Description("Number of storage devices")] + //[FieldOffset(25)] + public byte storage_count; - /// Variance in local position + /// Status of storage STORAGE_STATUS [Units("")] - [Description("Variance in local position")] - //[FieldOffset(60)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] - public float[] pos_variance; + [Description("Status of storage")] + //[FieldOffset(26)] + public /*STORAGE_STATUS*/byte status; - /// The attitude, represented as Quaternion + /// Type of storage STORAGE_TYPE [Units("")] - [Description("The attitude, represented as Quaternion")] - //[FieldOffset(72)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// Angular rate in roll axis [rad/s] - [Units("[rad/s]")] - [Description("Angular rate in roll axis")] - //[FieldOffset(88)] - public float roll_rate; - - /// Angular rate in pitch axis [rad/s] - [Units("[rad/s]")] - [Description("Angular rate in pitch axis")] - //[FieldOffset(92)] - public float pitch_rate; + [Description("Type of storage")] + //[FieldOffset(27)] + public /*STORAGE_TYPE*/byte type; - /// Angular rate in yaw axis [rad/s] - [Units("[rad/s]")] - [Description("Angular rate in yaw axis")] - //[FieldOffset(96)] - public float yaw_rate; + /// Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. + [Units("")] + [Description("Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.")] + //[FieldOffset(28)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] name; }; - /// extensions_start 9 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] - /// Battery information - public struct mavlink_battery_status_t + /// extensions_start 6 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] + /// Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. + public struct mavlink_camera_capture_status_t { /// packet ordered constructor - public mavlink_battery_status_t(int current_consumed,int energy_consumed,short temperature,ushort[] voltages,short current_battery,byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,sbyte battery_remaining,int time_remaining,/*MAV_BATTERY_CHARGE_STATE*/byte charge_state,ushort[] voltages_ext,/*MAV_BATTERY_MODE*/byte mode,/*MAV_BATTERY_FAULT*/uint fault_bitmask) + public mavlink_camera_capture_status_t(uint time_boot_ms,float image_interval,uint recording_time_ms,float available_capacity,byte image_status,byte video_status,int image_count) { - this.current_consumed = current_consumed; - this.energy_consumed = energy_consumed; - this.temperature = temperature; - this.voltages = voltages; - this.current_battery = current_battery; - this.id = id; - this.battery_function = battery_function; - this.type = type; - this.battery_remaining = battery_remaining; - this.time_remaining = time_remaining; - this.charge_state = charge_state; - this.voltages_ext = voltages_ext; - this.mode = mode; - this.fault_bitmask = fault_bitmask; + this.time_boot_ms = time_boot_ms; + this.image_interval = image_interval; + this.recording_time_ms = recording_time_ms; + this.available_capacity = available_capacity; + this.image_status = image_status; + this.video_status = video_status; + this.image_count = image_count; } /// packet xml order - public static mavlink_battery_status_t PopulateXMLOrder(byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,short temperature,ushort[] voltages,short current_battery,int current_consumed,int energy_consumed,sbyte battery_remaining,int time_remaining,/*MAV_BATTERY_CHARGE_STATE*/byte charge_state,ushort[] voltages_ext,/*MAV_BATTERY_MODE*/byte mode,/*MAV_BATTERY_FAULT*/uint fault_bitmask) + public static mavlink_camera_capture_status_t PopulateXMLOrder(uint time_boot_ms,byte image_status,byte video_status,float image_interval,uint recording_time_ms,float available_capacity,int image_count) { - var msg = new mavlink_battery_status_t(); + var msg = new mavlink_camera_capture_status_t(); - msg.id = id; - msg.battery_function = battery_function; - msg.type = type; - msg.temperature = temperature; - msg.voltages = voltages; - msg.current_battery = current_battery; - msg.current_consumed = current_consumed; - msg.energy_consumed = energy_consumed; - msg.battery_remaining = battery_remaining; - msg.time_remaining = time_remaining; - msg.charge_state = charge_state; - msg.voltages_ext = voltages_ext; - msg.mode = mode; - msg.fault_bitmask = fault_bitmask; + msg.time_boot_ms = time_boot_ms; + msg.image_status = image_status; + msg.video_status = video_status; + msg.image_interval = image_interval; + msg.recording_time_ms = recording_time_ms; + msg.available_capacity = available_capacity; + msg.image_count = image_count; return msg; } - /// Consumed charge, -1: autopilot does not provide consumption estimate [mAh] - [Units("[mAh]")] - [Description("Consumed charge, -1: autopilot does not provide consumption estimate")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public int current_consumed; + public uint time_boot_ms; - /// Consumed energy, -1: autopilot does not provide energy consumption estimate [hJ] - [Units("[hJ]")] - [Description("Consumed energy, -1: autopilot does not provide energy consumption estimate")] + /// Image capture interval [s] + [Units("[s]")] + [Description("Image capture interval")] //[FieldOffset(4)] - public int energy_consumed; + public float image_interval; - /// Temperature of the battery. INT16_MAX for unknown temperature. [cdegC] - [Units("[cdegC]")] - [Description("Temperature of the battery. INT16_MAX for unknown temperature.")] + /// Time since recording started [ms] + [Units("[ms]")] + [Description("Time since recording started")] //[FieldOffset(8)] - public short temperature; - - /// Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). [mV] - [Units("[mV]")] - [Description("Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).")] - //[FieldOffset(10)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public ushort[] voltages; - - /// Battery current, -1: autopilot does not measure the current [cA] - [Units("[cA]")] - [Description("Battery current, -1: autopilot does not measure the current")] - //[FieldOffset(30)] - public short current_battery; - - /// Battery ID - [Units("")] - [Description("Battery ID")] - //[FieldOffset(32)] - public byte id; - - /// Function of the battery MAV_BATTERY_FUNCTION - [Units("")] - [Description("Function of the battery")] - //[FieldOffset(33)] - public /*MAV_BATTERY_FUNCTION*/byte battery_function; - - /// Type (chemistry) of the battery MAV_BATTERY_TYPE - [Units("")] - [Description("Type (chemistry) of the battery")] - //[FieldOffset(34)] - public /*MAV_BATTERY_TYPE*/byte type; - - /// Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. [%] - [Units("[%]")] - [Description("Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.")] - //[FieldOffset(35)] - public sbyte battery_remaining; + public uint recording_time_ms; - /// Remaining battery time, 0: autopilot does not provide remaining battery time estimate [s] - [Units("[s]")] - [Description("Remaining battery time, 0: autopilot does not provide remaining battery time estimate")] - //[FieldOffset(36)] - public int time_remaining; + /// Available storage capacity. [MiB] + [Units("[MiB]")] + [Description("Available storage capacity.")] + //[FieldOffset(12)] + public float available_capacity; - /// State for extent of discharge, provided by autopilot for warning or external reactions MAV_BATTERY_CHARGE_STATE + /// Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) [Units("")] - [Description("State for extent of discharge, provided by autopilot for warning or external reactions")] - //[FieldOffset(40)] - public /*MAV_BATTERY_CHARGE_STATE*/byte charge_state; - - /// Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. [mV] - [Units("[mV]")] - [Description("Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.")] - //[FieldOffset(41)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public ushort[] voltages_ext; + [Description("Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)")] + //[FieldOffset(16)] + public byte image_status; - /// Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. MAV_BATTERY_MODE + /// Current status of video capturing (0: idle, 1: capture in progress) [Units("")] - [Description("Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.")] - //[FieldOffset(49)] - public /*MAV_BATTERY_MODE*/byte mode; + [Description("Current status of video capturing (0: idle, 1: capture in progress)")] + //[FieldOffset(17)] + public byte video_status; - /// Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). MAV_BATTERY_FAULT bitmask + /// Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). [Units("")] - [Description("Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).")] - //[FieldOffset(50)] - public /*MAV_BATTERY_FAULT*/uint fault_bitmask; + [Description("Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).")] + //[FieldOffset(18)] + public int image_count; }; - /// extensions_start 11 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=78)] - /// Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE. - public struct mavlink_autopilot_version_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] + /// Information about a captured image. This is emitted every time a message is captured. It may be re-requested using MAV_CMD_REQUEST_MESSAGE, using param2 to indicate the sequence number for the missing image. + public struct mavlink_camera_image_captured_t { /// packet ordered constructor - public mavlink_autopilot_version_t(/*MAV_PROTOCOL_CAPABILITY*/ulong capabilities,ulong uid,uint flight_sw_version,uint middleware_sw_version,uint os_sw_version,uint board_version,ushort vendor_id,ushort product_id,byte[] flight_custom_version,byte[] middleware_custom_version,byte[] os_custom_version,byte[] uid2) + public mavlink_camera_image_captured_t(ulong time_utc,uint time_boot_ms,int lat,int lon,int alt,int relative_alt,float[] q,int image_index,byte camera_id,sbyte capture_result,byte[] file_url) { - this.capabilities = capabilities; - this.uid = uid; - this.flight_sw_version = flight_sw_version; - this.middleware_sw_version = middleware_sw_version; - this.os_sw_version = os_sw_version; - this.board_version = board_version; - this.vendor_id = vendor_id; - this.product_id = product_id; - this.flight_custom_version = flight_custom_version; - this.middleware_custom_version = middleware_custom_version; - this.os_custom_version = os_custom_version; - this.uid2 = uid2; + this.time_utc = time_utc; + this.time_boot_ms = time_boot_ms; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.relative_alt = relative_alt; + this.q = q; + this.image_index = image_index; + this.camera_id = camera_id; + this.capture_result = capture_result; + this.file_url = file_url; } /// packet xml order - public static mavlink_autopilot_version_t PopulateXMLOrder(/*MAV_PROTOCOL_CAPABILITY*/ulong capabilities,uint flight_sw_version,uint middleware_sw_version,uint os_sw_version,uint board_version,byte[] flight_custom_version,byte[] middleware_custom_version,byte[] os_custom_version,ushort vendor_id,ushort product_id,ulong uid,byte[] uid2) + public static mavlink_camera_image_captured_t PopulateXMLOrder(uint time_boot_ms,ulong time_utc,byte camera_id,int lat,int lon,int alt,int relative_alt,float[] q,int image_index,sbyte capture_result,byte[] file_url) { - var msg = new mavlink_autopilot_version_t(); + var msg = new mavlink_camera_image_captured_t(); - msg.capabilities = capabilities; - msg.flight_sw_version = flight_sw_version; - msg.middleware_sw_version = middleware_sw_version; - msg.os_sw_version = os_sw_version; - msg.board_version = board_version; - msg.flight_custom_version = flight_custom_version; - msg.middleware_custom_version = middleware_custom_version; - msg.os_custom_version = os_custom_version; - msg.vendor_id = vendor_id; - msg.product_id = product_id; - msg.uid = uid; - msg.uid2 = uid2; + msg.time_boot_ms = time_boot_ms; + msg.time_utc = time_utc; + msg.camera_id = camera_id; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.relative_alt = relative_alt; + msg.q = q; + msg.image_index = image_index; + msg.capture_result = capture_result; + msg.file_url = file_url; return msg; } - /// Bitmap of capabilities MAV_PROTOCOL_CAPABILITY bitmask - [Units("")] - [Description("Bitmap of capabilities")] + /// Timestamp (time since UNIX epoch) in UTC. 0 for unknown. [us] + [Units("[us]")] + [Description("Timestamp (time since UNIX epoch) in UTC. 0 for unknown.")] //[FieldOffset(0)] - public /*MAV_PROTOCOL_CAPABILITY*/ulong capabilities; + public ulong time_utc; - /// UID if provided by hardware (see uid2) - [Units("")] - [Description("UID if provided by hardware (see uid2)")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(8)] - public ulong uid; + public uint time_boot_ms; - /// Firmware version number - [Units("")] - [Description("Firmware version number")] + /// Latitude where image was taken [degE7] + [Units("[degE7]")] + [Description("Latitude where image was taken")] + //[FieldOffset(12)] + public int lat; + + /// Longitude where capture was taken [degE7] + [Units("[degE7]")] + [Description("Longitude where capture was taken")] //[FieldOffset(16)] - public uint flight_sw_version; + public int lon; - /// Middleware version number - [Units("")] - [Description("Middleware version number")] + /// Altitude (MSL) where image was taken [mm] + [Units("[mm]")] + [Description("Altitude (MSL) where image was taken")] //[FieldOffset(20)] - public uint middleware_sw_version; + public int alt; - /// Operating system version number - [Units("")] - [Description("Operating system version number")] + /// Altitude above ground [mm] + [Units("[mm]")] + [Description("Altitude above ground")] //[FieldOffset(24)] - public uint os_sw_version; + public int relative_alt; - /// HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt + /// Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) [Units("")] - [Description("HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt")] + [Description("Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] //[FieldOffset(28)] - public uint board_version; - - /// ID of the board vendor - [Units("")] - [Description("ID of the board vendor")] - //[FieldOffset(32)] - public ushort vendor_id; - - /// ID of the product - [Units("")] - [Description("ID of the product")] - //[FieldOffset(34)] - public ushort product_id; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + /// Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) [Units("")] - [Description("Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.")] - //[FieldOffset(36)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public byte[] flight_custom_version; + [Description("Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)")] + //[FieldOffset(44)] + public int image_index; - /// Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + /// Deprecated/unused. Component IDs are used to differentiate multiple cameras. [Units("")] - [Description("Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.")] - //[FieldOffset(44)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public byte[] middleware_custom_version; + [Description("Deprecated/unused. Component IDs are used to differentiate multiple cameras.")] + //[FieldOffset(48)] + public byte camera_id; - /// Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + /// Boolean indicating success (1) or failure (0) while capturing this image. [Units("")] - [Description("Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.")] - //[FieldOffset(52)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public byte[] os_custom_version; + [Description("Boolean indicating success (1) or failure (0) while capturing this image.")] + //[FieldOffset(49)] + public sbyte capture_result; - /// UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) + /// URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. [Units("")] - [Description("UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)")] - //[FieldOffset(60)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=18)] - public byte[] uid2; + [Description("URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.")] + //[FieldOffset(50)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=205)] + public byte[] file_url; }; - /// extensions_start 8 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=60)] - /// The location of a landing target. See: https://mavlink.io/en/services/landing_target.html - public struct mavlink_landing_target_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] + /// Information about flight since last arming. + public struct mavlink_flight_information_t { /// packet ordered constructor - public mavlink_landing_target_t(ulong time_usec,float angle_x,float angle_y,float distance,float size_x,float size_y,byte target_num,/*MAV_FRAME*/byte frame,float x,float y,float z,float[] q,/*LANDING_TARGET_TYPE*/byte type,byte position_valid) + public mavlink_flight_information_t(ulong arming_time_utc,ulong takeoff_time_utc,ulong flight_uuid,uint time_boot_ms) { - this.time_usec = time_usec; - this.angle_x = angle_x; - this.angle_y = angle_y; - this.distance = distance; - this.size_x = size_x; - this.size_y = size_y; - this.target_num = target_num; - this.frame = frame; - this.x = x; - this.y = y; - this.z = z; - this.q = q; - this.type = type; - this.position_valid = position_valid; + this.arming_time_utc = arming_time_utc; + this.takeoff_time_utc = takeoff_time_utc; + this.flight_uuid = flight_uuid; + this.time_boot_ms = time_boot_ms; } /// packet xml order - public static mavlink_landing_target_t PopulateXMLOrder(ulong time_usec,byte target_num,/*MAV_FRAME*/byte frame,float angle_x,float angle_y,float distance,float size_x,float size_y,float x,float y,float z,float[] q,/*LANDING_TARGET_TYPE*/byte type,byte position_valid) + public static mavlink_flight_information_t PopulateXMLOrder(uint time_boot_ms,ulong arming_time_utc,ulong takeoff_time_utc,ulong flight_uuid) { - var msg = new mavlink_landing_target_t(); + var msg = new mavlink_flight_information_t(); - msg.time_usec = time_usec; - msg.target_num = target_num; - msg.frame = frame; - msg.angle_x = angle_x; - msg.angle_y = angle_y; - msg.distance = distance; - msg.size_x = size_x; - msg.size_y = size_y; - msg.x = x; - msg.y = y; - msg.z = z; - msg.q = q; - msg.type = type; - msg.position_valid = position_valid; + msg.time_boot_ms = time_boot_ms; + msg.arming_time_utc = arming_time_utc; + msg.takeoff_time_utc = takeoff_time_utc; + msg.flight_uuid = flight_uuid; return msg; } - /// 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. [us] + /// Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown [us] [Units("[us]")] - [Description("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.")] + [Description("Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown")] //[FieldOffset(0)] - public ulong time_usec; + public ulong arming_time_utc; - /// X-axis angular offset of the target from the center of the image [rad] - [Units("[rad]")] - [Description("X-axis angular offset of the target from the center of the image")] + /// Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown [us] + [Units("[us]")] + [Description("Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown")] //[FieldOffset(8)] - public float angle_x; - - /// Y-axis angular offset of the target from the center of the image [rad] - [Units("[rad]")] - [Description("Y-axis angular offset of the target from the center of the image")] - //[FieldOffset(12)] - public float angle_y; + public ulong takeoff_time_utc; - /// Distance to the target from the vehicle [m] - [Units("[m]")] - [Description("Distance to the target from the vehicle")] + /// Universally unique identifier (UUID) of flight, should correspond to name of log files + [Units("")] + [Description("Universally unique identifier (UUID) of flight, should correspond to name of log files")] //[FieldOffset(16)] - public float distance; - - /// Size of target along x-axis [rad] - [Units("[rad]")] - [Description("Size of target along x-axis")] - //[FieldOffset(20)] - public float size_x; + public ulong flight_uuid; - /// Size of target along y-axis [rad] - [Units("[rad]")] - [Description("Size of target along y-axis")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(24)] - public float size_y; - - /// The ID of the target if multiple targets are present - [Units("")] - [Description("The ID of the target if multiple targets are present")] - //[FieldOffset(28)] - public byte target_num; + public uint time_boot_ms; + }; - /// Coordinate frame used for following fields. MAV_FRAME - [Units("")] - [Description("Coordinate frame used for following fields.")] - //[FieldOffset(29)] - public /*MAV_FRAME*/byte frame; + + /// extensions_start 4 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Orientation of a mount + public struct mavlink_mount_orientation_t + { + /// packet ordered constructor + public mavlink_mount_orientation_t(uint time_boot_ms,float roll,float pitch,float yaw,float yaw_absolute) + { + this.time_boot_ms = time_boot_ms; + this.roll = roll; + this.pitch = pitch; + this.yaw = yaw; + this.yaw_absolute = yaw_absolute; + + } + + /// packet xml order + public static mavlink_mount_orientation_t PopulateXMLOrder(uint time_boot_ms,float roll,float pitch,float yaw,float yaw_absolute) + { + var msg = new mavlink_mount_orientation_t(); - /// X Position of the landing target in MAV_FRAME [m] - [Units("[m]")] - [Description("X Position of the landing target in MAV_FRAME")] - //[FieldOffset(30)] - public float x; + msg.time_boot_ms = time_boot_ms; + msg.roll = roll; + msg.pitch = pitch; + msg.yaw = yaw; + msg.yaw_absolute = yaw_absolute; + + return msg; + } + - /// Y Position of the landing target in MAV_FRAME [m] - [Units("[m]")] - [Description("Y Position of the landing target in MAV_FRAME")] - //[FieldOffset(34)] - public float y; + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; - /// Z Position of the landing target in MAV_FRAME [m] - [Units("[m]")] - [Description("Z Position of the landing target in MAV_FRAME")] - //[FieldOffset(38)] - public float z; + /// Roll in global frame (set to NaN for invalid). [deg] + [Units("[deg]")] + [Description("Roll in global frame (set to NaN for invalid).")] + //[FieldOffset(4)] + public float roll; - /// Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - [Units("")] - [Description("Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] - //[FieldOffset(42)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; + /// Pitch in global frame (set to NaN for invalid). [deg] + [Units("[deg]")] + [Description("Pitch in global frame (set to NaN for invalid).")] + //[FieldOffset(8)] + public float pitch; - /// Type of landing target LANDING_TARGET_TYPE - [Units("")] - [Description("Type of landing target")] - //[FieldOffset(58)] - public /*LANDING_TARGET_TYPE*/byte type; + /// Yaw relative to vehicle (set to NaN for invalid). [deg] + [Units("[deg]")] + [Description("Yaw relative to vehicle (set to NaN for invalid).")] + //[FieldOffset(12)] + public float yaw; - /// Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). - [Units("")] - [Description("Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).")] - //[FieldOffset(59)] - public byte position_valid; + /// Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). [deg] + [Units("[deg]")] + [Description("Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).")] + //[FieldOffset(16)] + public float yaw_absolute; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Status of geo-fencing. Sent in extended status stream when fencing enabled. - public struct mavlink_fence_status_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] + /// A message containing logged data (see also MAV_CMD_LOGGING_START) + public struct mavlink_logging_data_t { /// packet ordered constructor - public mavlink_fence_status_t(uint breach_time,ushort breach_count,byte breach_status,/*FENCE_BREACH*/byte breach_type,/*FENCE_MITIGATE*/byte breach_mitigation) + public mavlink_logging_data_t(ushort sequence,byte target_system,byte target_component,byte length,byte first_message_offset,byte[] data) { - this.breach_time = breach_time; - this.breach_count = breach_count; - this.breach_status = breach_status; - this.breach_type = breach_type; - this.breach_mitigation = breach_mitigation; + this.sequence = sequence; + this.target_system = target_system; + this.target_component = target_component; + this.length = length; + this.first_message_offset = first_message_offset; + this.data = data; } /// packet xml order - public static mavlink_fence_status_t PopulateXMLOrder(byte breach_status,ushort breach_count,/*FENCE_BREACH*/byte breach_type,uint breach_time,/*FENCE_MITIGATE*/byte breach_mitigation) + public static mavlink_logging_data_t PopulateXMLOrder(byte target_system,byte target_component,ushort sequence,byte length,byte first_message_offset,byte[] data) { - var msg = new mavlink_fence_status_t(); + var msg = new mavlink_logging_data_t(); - msg.breach_status = breach_status; - msg.breach_count = breach_count; - msg.breach_type = breach_type; - msg.breach_time = breach_time; - msg.breach_mitigation = breach_mitigation; + msg.target_system = target_system; + msg.target_component = target_component; + msg.sequence = sequence; + msg.length = length; + msg.first_message_offset = first_message_offset; + msg.data = data; return msg; } - /// Time (since boot) of last breach. [ms] - [Units("[ms]")] - [Description("Time (since boot) of last breach.")] + /// sequence number (can wrap) + [Units("")] + [Description("sequence number (can wrap)")] //[FieldOffset(0)] - public uint breach_time; + public ushort sequence; - /// Number of fence breaches. + /// system ID of the target [Units("")] - [Description("Number of fence breaches.")] - //[FieldOffset(4)] - public ushort breach_count; + [Description("system ID of the target")] + //[FieldOffset(2)] + public byte target_system; - /// Breach status (0 if currently inside fence, 1 if outside). + /// component ID of the target [Units("")] - [Description("Breach status (0 if currently inside fence, 1 if outside).")] - //[FieldOffset(6)] - public byte breach_status; + [Description("component ID of the target")] + //[FieldOffset(3)] + public byte target_component; - /// Last breach type. FENCE_BREACH - [Units("")] - [Description("Last breach type.")] - //[FieldOffset(7)] - public /*FENCE_BREACH*/byte breach_type; + /// data length [bytes] + [Units("[bytes]")] + [Description("data length")] + //[FieldOffset(4)] + public byte length; - /// Active action to prevent fence breach FENCE_MITIGATE + /// offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). [bytes] + [Units("[bytes]")] + [Description("offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).")] + //[FieldOffset(5)] + public byte first_message_offset; + + /// logged data [Units("")] - [Description("Active action to prevent fence breach")] - //[FieldOffset(8)] - public /*FENCE_MITIGATE*/byte breach_mitigation; + [Description("logged data")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=249)] + public byte[] data; }; - /// extensions_start 14 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] - /// Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. - public struct mavlink_mag_cal_report_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] + /// A message containing logged data which requires a LOGGING_ACK to be sent back + public struct mavlink_logging_data_acked_t { /// packet ordered constructor - public mavlink_mag_cal_report_t(float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte autosaved,float orientation_confidence,/*MAV_SENSOR_ORIENTATION*/byte old_orientation,/*MAV_SENSOR_ORIENTATION*/byte new_orientation,float scale_factor) + public mavlink_logging_data_acked_t(ushort sequence,byte target_system,byte target_component,byte length,byte first_message_offset,byte[] data) { - this.fitness = fitness; - this.ofs_x = ofs_x; - this.ofs_y = ofs_y; - this.ofs_z = ofs_z; - this.diag_x = diag_x; - this.diag_y = diag_y; - this.diag_z = diag_z; - this.offdiag_x = offdiag_x; - this.offdiag_y = offdiag_y; - this.offdiag_z = offdiag_z; - this.compass_id = compass_id; - this.cal_mask = cal_mask; - this.cal_status = cal_status; - this.autosaved = autosaved; - this.orientation_confidence = orientation_confidence; - this.old_orientation = old_orientation; - this.new_orientation = new_orientation; - this.scale_factor = scale_factor; + this.sequence = sequence; + this.target_system = target_system; + this.target_component = target_component; + this.length = length; + this.first_message_offset = first_message_offset; + this.data = data; } /// packet xml order - public static mavlink_mag_cal_report_t PopulateXMLOrder(byte compass_id,byte cal_mask,/*MAG_CAL_STATUS*/byte cal_status,byte autosaved,float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,float orientation_confidence,/*MAV_SENSOR_ORIENTATION*/byte old_orientation,/*MAV_SENSOR_ORIENTATION*/byte new_orientation,float scale_factor) + public static mavlink_logging_data_acked_t PopulateXMLOrder(byte target_system,byte target_component,ushort sequence,byte length,byte first_message_offset,byte[] data) { - var msg = new mavlink_mag_cal_report_t(); + var msg = new mavlink_logging_data_acked_t(); - msg.compass_id = compass_id; - msg.cal_mask = cal_mask; - msg.cal_status = cal_status; - msg.autosaved = autosaved; - msg.fitness = fitness; - msg.ofs_x = ofs_x; - msg.ofs_y = ofs_y; - msg.ofs_z = ofs_z; - msg.diag_x = diag_x; - msg.diag_y = diag_y; - msg.diag_z = diag_z; - msg.offdiag_x = offdiag_x; - msg.offdiag_y = offdiag_y; - msg.offdiag_z = offdiag_z; - msg.orientation_confidence = orientation_confidence; - msg.old_orientation = old_orientation; - msg.new_orientation = new_orientation; - msg.scale_factor = scale_factor; + msg.target_system = target_system; + msg.target_component = target_component; + msg.sequence = sequence; + msg.length = length; + msg.first_message_offset = first_message_offset; + msg.data = data; return msg; } - /// RMS milligauss residuals. [mgauss] - [Units("[mgauss]")] - [Description("RMS milligauss residuals.")] - //[FieldOffset(0)] - public float fitness; - - /// X offset. - [Units("")] - [Description("X offset.")] - //[FieldOffset(4)] - public float ofs_x; - - /// Y offset. - [Units("")] - [Description("Y offset.")] - //[FieldOffset(8)] - public float ofs_y; - - /// Z offset. - [Units("")] - [Description("Z offset.")] - //[FieldOffset(12)] - public float ofs_z; - - /// X diagonal (matrix 11). - [Units("")] - [Description("X diagonal (matrix 11).")] - //[FieldOffset(16)] - public float diag_x; - - /// Y diagonal (matrix 22). - [Units("")] - [Description("Y diagonal (matrix 22).")] - //[FieldOffset(20)] - public float diag_y; - - /// Z diagonal (matrix 33). - [Units("")] - [Description("Z diagonal (matrix 33).")] - //[FieldOffset(24)] - public float diag_z; - - /// X off-diagonal (matrix 12 and 21). - [Units("")] - [Description("X off-diagonal (matrix 12 and 21).")] - //[FieldOffset(28)] - public float offdiag_x; - - /// Y off-diagonal (matrix 13 and 31). - [Units("")] - [Description("Y off-diagonal (matrix 13 and 31).")] - //[FieldOffset(32)] - public float offdiag_y; - - /// Z off-diagonal (matrix 32 and 23). - [Units("")] - [Description("Z off-diagonal (matrix 32 and 23).")] - //[FieldOffset(36)] - public float offdiag_z; - - /// Compass being calibrated. - [Units("")] - [Description("Compass being calibrated.")] - //[FieldOffset(40)] - public byte compass_id; - - /// Bitmask of compasses being calibrated. bitmask - [Units("")] - [Description("Bitmask of compasses being calibrated.")] - //[FieldOffset(41)] - public byte cal_mask; - - /// Calibration Status. MAG_CAL_STATUS + /// sequence number (can wrap) [Units("")] - [Description("Calibration Status.")] - //[FieldOffset(42)] - public /*MAG_CAL_STATUS*/byte cal_status; + [Description("sequence number (can wrap)")] + //[FieldOffset(0)] + public ushort sequence; - /// 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. + /// system ID of the target [Units("")] - [Description("0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.")] - //[FieldOffset(43)] - public byte autosaved; + [Description("system ID of the target")] + //[FieldOffset(2)] + public byte target_system; - /// Confidence in orientation (higher is better). + /// component ID of the target [Units("")] - [Description("Confidence in orientation (higher is better).")] - //[FieldOffset(44)] - public float orientation_confidence; + [Description("component ID of the target")] + //[FieldOffset(3)] + public byte target_component; - /// orientation before calibration. MAV_SENSOR_ORIENTATION - [Units("")] - [Description("orientation before calibration.")] - //[FieldOffset(48)] - public /*MAV_SENSOR_ORIENTATION*/byte old_orientation; + /// data length [bytes] + [Units("[bytes]")] + [Description("data length")] + //[FieldOffset(4)] + public byte length; - /// orientation after calibration. MAV_SENSOR_ORIENTATION - [Units("")] - [Description("orientation after calibration.")] - //[FieldOffset(49)] - public /*MAV_SENSOR_ORIENTATION*/byte new_orientation; + /// offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). [bytes] + [Units("[bytes]")] + [Description("offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).")] + //[FieldOffset(5)] + public byte first_message_offset; - /// field radius correction factor + /// logged data [Units("")] - [Description("field radius correction factor")] - //[FieldOffset(50)] - public float scale_factor; + [Description("logged data")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=249)] + public byte[] data; }; - /// extensions_start 17 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=73)] - /// EFI status output - public struct mavlink_efi_status_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// An ack for a LOGGING_DATA_ACKED message + public struct mavlink_logging_ack_t { /// packet ordered constructor - public mavlink_efi_status_t(float ecu_index,float rpm,float fuel_consumed,float fuel_flow,float engine_load,float throttle_position,float spark_dwell_time,float barometric_pressure,float intake_manifold_pressure,float intake_manifold_temperature,float cylinder_head_temperature,float ignition_timing,float injection_time,float exhaust_gas_temperature,float throttle_out,float pt_compensation,byte health,float ignition_voltage,float fuel_pressure) + public mavlink_logging_ack_t(ushort sequence,byte target_system,byte target_component) { - this.ecu_index = ecu_index; - this.rpm = rpm; - this.fuel_consumed = fuel_consumed; - this.fuel_flow = fuel_flow; - this.engine_load = engine_load; - this.throttle_position = throttle_position; - this.spark_dwell_time = spark_dwell_time; - this.barometric_pressure = barometric_pressure; - this.intake_manifold_pressure = intake_manifold_pressure; - this.intake_manifold_temperature = intake_manifold_temperature; - this.cylinder_head_temperature = cylinder_head_temperature; - this.ignition_timing = ignition_timing; - this.injection_time = injection_time; - this.exhaust_gas_temperature = exhaust_gas_temperature; - this.throttle_out = throttle_out; - this.pt_compensation = pt_compensation; - this.health = health; - this.ignition_voltage = ignition_voltage; - this.fuel_pressure = fuel_pressure; + this.sequence = sequence; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_efi_status_t PopulateXMLOrder(byte health,float ecu_index,float rpm,float fuel_consumed,float fuel_flow,float engine_load,float throttle_position,float spark_dwell_time,float barometric_pressure,float intake_manifold_pressure,float intake_manifold_temperature,float cylinder_head_temperature,float ignition_timing,float injection_time,float exhaust_gas_temperature,float throttle_out,float pt_compensation,float ignition_voltage,float fuel_pressure) + public static mavlink_logging_ack_t PopulateXMLOrder(byte target_system,byte target_component,ushort sequence) { - var msg = new mavlink_efi_status_t(); + var msg = new mavlink_logging_ack_t(); - msg.health = health; - msg.ecu_index = ecu_index; - msg.rpm = rpm; - msg.fuel_consumed = fuel_consumed; - msg.fuel_flow = fuel_flow; - msg.engine_load = engine_load; - msg.throttle_position = throttle_position; - msg.spark_dwell_time = spark_dwell_time; - msg.barometric_pressure = barometric_pressure; - msg.intake_manifold_pressure = intake_manifold_pressure; - msg.intake_manifold_temperature = intake_manifold_temperature; - msg.cylinder_head_temperature = cylinder_head_temperature; - msg.ignition_timing = ignition_timing; - msg.injection_time = injection_time; - msg.exhaust_gas_temperature = exhaust_gas_temperature; - msg.throttle_out = throttle_out; - msg.pt_compensation = pt_compensation; - msg.ignition_voltage = ignition_voltage; - msg.fuel_pressure = fuel_pressure; + msg.target_system = target_system; + msg.target_component = target_component; + msg.sequence = sequence; return msg; } - /// ECU index + /// sequence number (must match the one in LOGGING_DATA_ACKED) [Units("")] - [Description("ECU index")] + [Description("sequence number (must match the one in LOGGING_DATA_ACKED)")] //[FieldOffset(0)] - public float ecu_index; - - /// RPM - [Units("")] - [Description("RPM")] - //[FieldOffset(4)] - public float rpm; - - /// Fuel consumed [cm^3] - [Units("[cm^3]")] - [Description("Fuel consumed")] - //[FieldOffset(8)] - public float fuel_consumed; - - /// Fuel flow rate [cm^3/min] - [Units("[cm^3/min]")] - [Description("Fuel flow rate")] - //[FieldOffset(12)] - public float fuel_flow; - - /// Engine load [%] - [Units("[%]")] - [Description("Engine load")] - //[FieldOffset(16)] - public float engine_load; - - /// Throttle position [%] - [Units("[%]")] - [Description("Throttle position")] - //[FieldOffset(20)] - public float throttle_position; - - /// Spark dwell time [ms] - [Units("[ms]")] - [Description("Spark dwell time")] - //[FieldOffset(24)] - public float spark_dwell_time; - - /// Barometric pressure [kPa] - [Units("[kPa]")] - [Description("Barometric pressure")] - //[FieldOffset(28)] - public float barometric_pressure; - - /// Intake manifold pressure( [kPa] - [Units("[kPa]")] - [Description("Intake manifold pressure(")] - //[FieldOffset(32)] - public float intake_manifold_pressure; - - /// Intake manifold temperature [degC] - [Units("[degC]")] - [Description("Intake manifold temperature")] - //[FieldOffset(36)] - public float intake_manifold_temperature; - - /// Cylinder head temperature [degC] - [Units("[degC]")] - [Description("Cylinder head temperature")] - //[FieldOffset(40)] - public float cylinder_head_temperature; - - /// Ignition timing (Crank angle degrees) [deg] - [Units("[deg]")] - [Description("Ignition timing (Crank angle degrees)")] - //[FieldOffset(44)] - public float ignition_timing; - - /// Injection time [ms] - [Units("[ms]")] - [Description("Injection time")] - //[FieldOffset(48)] - public float injection_time; - - /// Exhaust gas temperature [degC] - [Units("[degC]")] - [Description("Exhaust gas temperature")] - //[FieldOffset(52)] - public float exhaust_gas_temperature; - - /// Output throttle [%] - [Units("[%]")] - [Description("Output throttle")] - //[FieldOffset(56)] - public float throttle_out; + public ushort sequence; - /// Pressure/temperature compensation + /// system ID of the target [Units("")] - [Description("Pressure/temperature compensation")] - //[FieldOffset(60)] - public float pt_compensation; + [Description("system ID of the target")] + //[FieldOffset(2)] + public byte target_system; - /// EFI health status + /// component ID of the target [Units("")] - [Description("EFI health status")] - //[FieldOffset(64)] - public byte health; - - /// Supply voltage to EFI sparking system. Zero in this value means 'unknown', so if the supply voltage really is zero volts use 0.0001 instead. [V] - [Units("[V]")] - [Description("Supply voltage to EFI sparking system. Zero in this value means 'unknown', so if the supply voltage really is zero volts use 0.0001 instead.")] - //[FieldOffset(65)] - public float ignition_voltage; - - /// Fuel pressure. Zero in this value means 'unknown', so if the fuel pressure really is zero kPa use 0.0001 instead. [kPa] - [Units("[kPa]")] - [Description("Fuel pressure. Zero in this value means 'unknown', so if the fuel pressure really is zero kPa use 0.0001 instead.")] - //[FieldOffset(69)] - public float fuel_pressure; + [Description("component ID of the target")] + //[FieldOffset(3)] + public byte target_component; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. - public struct mavlink_estimator_status_t + /// extensions_start 12 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=214)] + /// Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc. + public struct mavlink_video_stream_information_t { /// packet ordered constructor - public mavlink_estimator_status_t(ulong time_usec,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy,/*ESTIMATOR_STATUS_FLAGS*/ushort flags) + public mavlink_video_stream_information_t(float framerate,uint bitrate,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,ushort resolution_h,ushort resolution_v,ushort rotation,ushort hfov,byte stream_id,byte count,/*VIDEO_STREAM_TYPE*/byte type,byte[] name,byte[] uri,/*VIDEO_STREAM_ENCODING*/byte encoding) { - this.time_usec = time_usec; - this.vel_ratio = vel_ratio; - this.pos_horiz_ratio = pos_horiz_ratio; - this.pos_vert_ratio = pos_vert_ratio; - this.mag_ratio = mag_ratio; - this.hagl_ratio = hagl_ratio; - this.tas_ratio = tas_ratio; - this.pos_horiz_accuracy = pos_horiz_accuracy; - this.pos_vert_accuracy = pos_vert_accuracy; + this.framerate = framerate; + this.bitrate = bitrate; this.flags = flags; + this.resolution_h = resolution_h; + this.resolution_v = resolution_v; + this.rotation = rotation; + this.hfov = hfov; + this.stream_id = stream_id; + this.count = count; + this.type = type; + this.name = name; + this.uri = uri; + this.encoding = encoding; } /// packet xml order - public static mavlink_estimator_status_t PopulateXMLOrder(ulong time_usec,/*ESTIMATOR_STATUS_FLAGS*/ushort flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) + public static mavlink_video_stream_information_t PopulateXMLOrder(byte stream_id,byte count,/*VIDEO_STREAM_TYPE*/byte type,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,ushort hfov,byte[] name,byte[] uri,/*VIDEO_STREAM_ENCODING*/byte encoding) { - var msg = new mavlink_estimator_status_t(); + var msg = new mavlink_video_stream_information_t(); - msg.time_usec = time_usec; + msg.stream_id = stream_id; + msg.count = count; + msg.type = type; msg.flags = flags; - msg.vel_ratio = vel_ratio; - msg.pos_horiz_ratio = pos_horiz_ratio; - msg.pos_vert_ratio = pos_vert_ratio; - msg.mag_ratio = mag_ratio; - msg.hagl_ratio = hagl_ratio; - msg.tas_ratio = tas_ratio; - msg.pos_horiz_accuracy = pos_horiz_accuracy; - msg.pos_vert_accuracy = pos_vert_accuracy; + msg.framerate = framerate; + msg.resolution_h = resolution_h; + msg.resolution_v = resolution_v; + msg.bitrate = bitrate; + msg.rotation = rotation; + msg.hfov = hfov; + msg.name = name; + msg.uri = uri; + msg.encoding = encoding; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Frame rate. [Hz] + [Units("[Hz]")] + [Description("Frame rate.")] //[FieldOffset(0)] - public ulong time_usec; + public float framerate; - /// Velocity innovation test ratio + /// Bit rate. [bits/s] + [Units("[bits/s]")] + [Description("Bit rate.")] + //[FieldOffset(4)] + public uint bitrate; + + /// Bitmap of stream status flags. VIDEO_STREAM_STATUS_FLAGS [Units("")] - [Description("Velocity innovation test ratio")] + [Description("Bitmap of stream status flags.")] //[FieldOffset(8)] - public float vel_ratio; + public /*VIDEO_STREAM_STATUS_FLAGS*/ushort flags; + + /// Horizontal resolution. [pix] + [Units("[pix]")] + [Description("Horizontal resolution.")] + //[FieldOffset(10)] + public ushort resolution_h; + + /// Vertical resolution. [pix] + [Units("[pix]")] + [Description("Vertical resolution.")] + //[FieldOffset(12)] + public ushort resolution_v; + + /// Video image rotation clockwise. [deg] + [Units("[deg]")] + [Description("Video image rotation clockwise.")] + //[FieldOffset(14)] + public ushort rotation; + + /// Horizontal Field of view. [deg] + [Units("[deg]")] + [Description("Horizontal Field of view.")] + //[FieldOffset(16)] + public ushort hfov; - /// Horizontal position innovation test ratio + /// Video Stream ID (1 for first, 2 for second, etc.) [Units("")] - [Description("Horizontal position innovation test ratio")] - //[FieldOffset(12)] - public float pos_horiz_ratio; + [Description("Video Stream ID (1 for first, 2 for second, etc.)")] + //[FieldOffset(18)] + public byte stream_id; - /// Vertical position innovation test ratio + /// Number of streams available. [Units("")] - [Description("Vertical position innovation test ratio")] - //[FieldOffset(16)] - public float pos_vert_ratio; + [Description("Number of streams available.")] + //[FieldOffset(19)] + public byte count; - /// Magnetometer innovation test ratio + /// Type of stream. VIDEO_STREAM_TYPE [Units("")] - [Description("Magnetometer innovation test ratio")] + [Description("Type of stream.")] //[FieldOffset(20)] - public float mag_ratio; + public /*VIDEO_STREAM_TYPE*/byte type; - /// Height above terrain innovation test ratio + /// Stream name. [Units("")] - [Description("Height above terrain innovation test ratio")] - //[FieldOffset(24)] - public float hagl_ratio; + [Description("Stream name.")] + //[FieldOffset(21)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] name; - /// True airspeed innovation test ratio + /// Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). [Units("")] - [Description("True airspeed innovation test ratio")] - //[FieldOffset(28)] - public float tas_ratio; - - /// Horizontal position 1-STD accuracy relative to the EKF local origin [m] - [Units("[m]")] - [Description("Horizontal position 1-STD accuracy relative to the EKF local origin")] - //[FieldOffset(32)] - public float pos_horiz_accuracy; - - /// Vertical position 1-STD accuracy relative to the EKF local origin [m] - [Units("[m]")] - [Description("Vertical position 1-STD accuracy relative to the EKF local origin")] - //[FieldOffset(36)] - public float pos_vert_accuracy; + [Description("Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).")] + //[FieldOffset(53)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=160)] + public byte[] uri; - /// Bitmap indicating which EKF outputs are valid. ESTIMATOR_STATUS_FLAGS bitmask + /// Encoding of stream. VIDEO_STREAM_ENCODING [Units("")] - [Description("Bitmap indicating which EKF outputs are valid.")] - //[FieldOffset(40)] - public /*ESTIMATOR_STATUS_FLAGS*/ushort flags; + [Description("Encoding of stream.")] + //[FieldOffset(213)] + public /*VIDEO_STREAM_ENCODING*/byte encoding; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] - /// Wind covariance estimate from vehicle. - public struct mavlink_wind_cov_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] + /// Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE. + public struct mavlink_video_stream_status_t { /// packet ordered constructor - public mavlink_wind_cov_t(ulong time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) + public mavlink_video_stream_status_t(float framerate,uint bitrate,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,ushort resolution_h,ushort resolution_v,ushort rotation,ushort hfov,byte stream_id) { - this.time_usec = time_usec; - this.wind_x = wind_x; - this.wind_y = wind_y; - this.wind_z = wind_z; - this.var_horiz = var_horiz; - this.var_vert = var_vert; - this.wind_alt = wind_alt; - this.horiz_accuracy = horiz_accuracy; - this.vert_accuracy = vert_accuracy; + this.framerate = framerate; + this.bitrate = bitrate; + this.flags = flags; + this.resolution_h = resolution_h; + this.resolution_v = resolution_v; + this.rotation = rotation; + this.hfov = hfov; + this.stream_id = stream_id; } /// packet xml order - public static mavlink_wind_cov_t PopulateXMLOrder(ulong time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) + public static mavlink_video_stream_status_t PopulateXMLOrder(byte stream_id,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,ushort hfov) { - var msg = new mavlink_wind_cov_t(); + var msg = new mavlink_video_stream_status_t(); - msg.time_usec = time_usec; - msg.wind_x = wind_x; - msg.wind_y = wind_y; - msg.wind_z = wind_z; - msg.var_horiz = var_horiz; - msg.var_vert = var_vert; - msg.wind_alt = wind_alt; - msg.horiz_accuracy = horiz_accuracy; - msg.vert_accuracy = vert_accuracy; + msg.stream_id = stream_id; + msg.flags = flags; + msg.framerate = framerate; + msg.resolution_h = resolution_h; + msg.resolution_v = resolution_v; + msg.bitrate = bitrate; + msg.rotation = rotation; + msg.hfov = hfov; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Frame rate [Hz] + [Units("[Hz]")] + [Description("Frame rate")] //[FieldOffset(0)] - public ulong time_usec; - - /// Wind in X (NED) direction [m/s] - [Units("[m/s]")] - [Description("Wind in X (NED) direction")] - //[FieldOffset(8)] - public float wind_x; + public float framerate; - /// Wind in Y (NED) direction [m/s] - [Units("[m/s]")] - [Description("Wind in Y (NED) direction")] - //[FieldOffset(12)] - public float wind_y; + /// Bit rate [bits/s] + [Units("[bits/s]")] + [Description("Bit rate")] + //[FieldOffset(4)] + public uint bitrate; - /// Wind in Z (NED) direction [m/s] - [Units("[m/s]")] - [Description("Wind in Z (NED) direction")] - //[FieldOffset(16)] - public float wind_z; + /// Bitmap of stream status flags VIDEO_STREAM_STATUS_FLAGS + [Units("")] + [Description("Bitmap of stream status flags")] + //[FieldOffset(8)] + public /*VIDEO_STREAM_STATUS_FLAGS*/ushort flags; - /// Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. [m/s] - [Units("[m/s]")] - [Description("Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.")] - //[FieldOffset(20)] - public float var_horiz; + /// Horizontal resolution [pix] + [Units("[pix]")] + [Description("Horizontal resolution")] + //[FieldOffset(10)] + public ushort resolution_h; - /// Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. [m/s] - [Units("[m/s]")] - [Description("Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.")] - //[FieldOffset(24)] - public float var_vert; + /// Vertical resolution [pix] + [Units("[pix]")] + [Description("Vertical resolution")] + //[FieldOffset(12)] + public ushort resolution_v; - /// Altitude (MSL) that this measurement was taken at [m] - [Units("[m]")] - [Description("Altitude (MSL) that this measurement was taken at")] - //[FieldOffset(28)] - public float wind_alt; + /// Video image rotation clockwise [deg] + [Units("[deg]")] + [Description("Video image rotation clockwise")] + //[FieldOffset(14)] + public ushort rotation; - /// Horizontal speed 1-STD accuracy [m] - [Units("[m]")] - [Description("Horizontal speed 1-STD accuracy")] - //[FieldOffset(32)] - public float horiz_accuracy; + /// Horizontal Field of view [deg] + [Units("[deg]")] + [Description("Horizontal Field of view")] + //[FieldOffset(16)] + public ushort hfov; - /// Vertical speed 1-STD accuracy [m] - [Units("[m]")] - [Description("Vertical speed 1-STD accuracy")] - //[FieldOffset(36)] - public float vert_accuracy; + /// Video Stream ID (1 for first, 2 for second, etc.) + [Units("")] + [Description("Video Stream ID (1 for first, 2 for second, etc.)")] + //[FieldOffset(18)] + public byte stream_id; }; - /// extensions_start 18 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=65)] - /// GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system. - public struct mavlink_gps_input_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] + /// Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. + public struct mavlink_camera_fov_status_t { /// packet ordered constructor - public mavlink_gps_input_t(ulong time_usec,uint time_week_ms,int lat,int lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,/*GPS_INPUT_IGNORE_FLAGS*/ushort ignore_flags,ushort time_week,byte gps_id,byte fix_type,byte satellites_visible,ushort yaw) + public mavlink_camera_fov_status_t(uint time_boot_ms,int lat_camera,int lon_camera,int alt_camera,int lat_image,int lon_image,int alt_image,float[] q,float hfov,float vfov) { - this.time_usec = time_usec; - this.time_week_ms = time_week_ms; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.hdop = hdop; - this.vdop = vdop; - this.vn = vn; - this.ve = ve; - this.vd = vd; - this.speed_accuracy = speed_accuracy; - this.horiz_accuracy = horiz_accuracy; - this.vert_accuracy = vert_accuracy; - this.ignore_flags = ignore_flags; - this.time_week = time_week; - this.gps_id = gps_id; - this.fix_type = fix_type; - this.satellites_visible = satellites_visible; - this.yaw = yaw; + this.time_boot_ms = time_boot_ms; + this.lat_camera = lat_camera; + this.lon_camera = lon_camera; + this.alt_camera = alt_camera; + this.lat_image = lat_image; + this.lon_image = lon_image; + this.alt_image = alt_image; + this.q = q; + this.hfov = hfov; + this.vfov = vfov; } /// packet xml order - public static mavlink_gps_input_t PopulateXMLOrder(ulong time_usec,byte gps_id,/*GPS_INPUT_IGNORE_FLAGS*/ushort ignore_flags,uint time_week_ms,ushort time_week,byte fix_type,int lat,int lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,byte satellites_visible,ushort yaw) + public static mavlink_camera_fov_status_t PopulateXMLOrder(uint time_boot_ms,int lat_camera,int lon_camera,int alt_camera,int lat_image,int lon_image,int alt_image,float[] q,float hfov,float vfov) { - var msg = new mavlink_gps_input_t(); + var msg = new mavlink_camera_fov_status_t(); - msg.time_usec = time_usec; - msg.gps_id = gps_id; - msg.ignore_flags = ignore_flags; - msg.time_week_ms = time_week_ms; - msg.time_week = time_week; - msg.fix_type = fix_type; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.hdop = hdop; - msg.vdop = vdop; - msg.vn = vn; - msg.ve = ve; - msg.vd = vd; - msg.speed_accuracy = speed_accuracy; - msg.horiz_accuracy = horiz_accuracy; - msg.vert_accuracy = vert_accuracy; - msg.satellites_visible = satellites_visible; - msg.yaw = yaw; + msg.time_boot_ms = time_boot_ms; + msg.lat_camera = lat_camera; + msg.lon_camera = lon_camera; + msg.alt_camera = alt_camera; + msg.lat_image = lat_image; + msg.lon_image = lon_image; + msg.alt_image = alt_image; + msg.q = q; + msg.hfov = hfov; + msg.vfov = vfov; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// GPS time (from start of GPS week) [ms] - [Units("[ms]")] - [Description("GPS time (from start of GPS week)")] - //[FieldOffset(8)] - public uint time_week_ms; + /// Latitude of camera (INT32_MAX if unknown). [degE7] + [Units("[degE7]")] + [Description("Latitude of camera (INT32_MAX if unknown).")] + //[FieldOffset(4)] + public int lat_camera; - /// Latitude (WGS84) [degE7] + /// Longitude of camera (INT32_MAX if unknown). [degE7] [Units("[degE7]")] - [Description("Latitude (WGS84)")] + [Description("Longitude of camera (INT32_MAX if unknown).")] + //[FieldOffset(8)] + public int lon_camera; + + /// Altitude (MSL) of camera (INT32_MAX if unknown). [mm] + [Units("[mm]")] + [Description("Altitude (MSL) of camera (INT32_MAX if unknown).")] //[FieldOffset(12)] - public int lat; + public int alt_camera; - /// Longitude (WGS84) [degE7] + /// Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). [degE7] [Units("[degE7]")] - [Description("Longitude (WGS84)")] + [Description("Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).")] //[FieldOffset(16)] - public int lon; + public int lat_image; - /// Altitude (MSL). Positive for up. [m] - [Units("[m]")] - [Description("Altitude (MSL). Positive for up.")] + /// Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). [degE7] + [Units("[degE7]")] + [Description("Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).")] //[FieldOffset(20)] - public float alt; + public int lon_image; - /// GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - [Units("")] - [Description("GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX")] + /// Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). [mm] + [Units("[mm]")] + [Description("Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).")] //[FieldOffset(24)] - public float hdop; + public int alt_image; - /// GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + /// Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) [Units("")] - [Description("GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX")] + [Description("Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] //[FieldOffset(28)] - public float vdop; - - /// GPS velocity in north direction in earth-fixed NED frame [m/s] - [Units("[m/s]")] - [Description("GPS velocity in north direction in earth-fixed NED frame")] - //[FieldOffset(32)] - public float vn; - - /// GPS velocity in east direction in earth-fixed NED frame [m/s] - [Units("[m/s]")] - [Description("GPS velocity in east direction in earth-fixed NED frame")] - //[FieldOffset(36)] - public float ve; - - /// GPS velocity in down direction in earth-fixed NED frame [m/s] - [Units("[m/s]")] - [Description("GPS velocity in down direction in earth-fixed NED frame")] - //[FieldOffset(40)] - public float vd; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// GPS speed accuracy [m/s] - [Units("[m/s]")] - [Description("GPS speed accuracy")] + /// Horizontal field of view (NaN if unknown). [deg] + [Units("[deg]")] + [Description("Horizontal field of view (NaN if unknown).")] //[FieldOffset(44)] - public float speed_accuracy; + public float hfov; - /// GPS horizontal accuracy [m] - [Units("[m]")] - [Description("GPS horizontal accuracy")] + /// Vertical field of view (NaN if unknown). [deg] + [Units("[deg]")] + [Description("Vertical field of view (NaN if unknown).")] //[FieldOffset(48)] - public float horiz_accuracy; - - /// GPS vertical accuracy [m] - [Units("[m]")] - [Description("GPS vertical accuracy")] - //[FieldOffset(52)] - public float vert_accuracy; - - /// Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. GPS_INPUT_IGNORE_FLAGS bitmask - [Units("")] - [Description("Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.")] - //[FieldOffset(56)] - public /*GPS_INPUT_IGNORE_FLAGS*/ushort ignore_flags; - - /// GPS week number - [Units("")] - [Description("GPS week number")] - //[FieldOffset(58)] - public ushort time_week; - - /// ID of the GPS for multiple GPS inputs - [Units("")] - [Description("ID of the GPS for multiple GPS inputs")] - //[FieldOffset(60)] - public byte gps_id; - - /// 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - [Units("")] - [Description("0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK")] - //[FieldOffset(61)] - public byte fix_type; - - /// Number of satellites visible. - [Units("")] - [Description("Number of satellites visible.")] - //[FieldOffset(62)] - public byte satellites_visible; - - /// Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north [cdeg] - [Units("[cdeg]")] - [Description("Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north")] - //[FieldOffset(63)] - public ushort yaw; + public float vfov; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=182)] - /// RTCM message for injecting into the onboard GPS (used for DGPS) - public struct mavlink_gps_rtcm_data_t - { - /// packet ordered constructor - public mavlink_gps_rtcm_data_t(byte flags,byte len,byte[] data) - { - this.flags = flags; - this.len = len; - this.data = data; - - } - - /// packet xml order - public static mavlink_gps_rtcm_data_t PopulateXMLOrder(byte flags,byte len,byte[] data) - { - var msg = new mavlink_gps_rtcm_data_t(); - - msg.flags = flags; - msg.len = len; - msg.data = data; - - return msg; - } - - - /// LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - [Units("")] - [Description("LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.")] - //[FieldOffset(0)] - public byte flags; - - /// data length [bytes] - [Units("[bytes]")] - [Description("data length")] - //[FieldOffset(1)] - public byte len; - - /// RTCM message (may be fragmented) - [Units("")] - [Description("RTCM message (may be fragmented)")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=180)] - public byte[] data; - }; - - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] - /// Message appropriate for high latency connections like Iridium - public struct mavlink_high_latency_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)] + /// Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval. + public struct mavlink_camera_tracking_image_status_t { /// packet ordered constructor - public mavlink_high_latency_t(uint custom_mode,int latitude,int longitude,short roll,short pitch,ushort heading,short heading_sp,short altitude_amsl,short altitude_sp,ushort wp_distance,/*MAV_MODE_FLAG*/byte base_mode,/*MAV_LANDED_STATE*/byte landed_state,sbyte throttle,byte airspeed,byte airspeed_sp,byte groundspeed,sbyte climb_rate,byte gps_nsat,/*GPS_FIX_TYPE*/byte gps_fix_type,byte battery_remaining,sbyte temperature,sbyte temperature_air,byte failsafe,byte wp_num) - { - this.custom_mode = custom_mode; - this.latitude = latitude; - this.longitude = longitude; - this.roll = roll; - this.pitch = pitch; - this.heading = heading; - this.heading_sp = heading_sp; - this.altitude_amsl = altitude_amsl; - this.altitude_sp = altitude_sp; - this.wp_distance = wp_distance; - this.base_mode = base_mode; - this.landed_state = landed_state; - this.throttle = throttle; - this.airspeed = airspeed; - this.airspeed_sp = airspeed_sp; - this.groundspeed = groundspeed; - this.climb_rate = climb_rate; - this.gps_nsat = gps_nsat; - this.gps_fix_type = gps_fix_type; - this.battery_remaining = battery_remaining; - this.temperature = temperature; - this.temperature_air = temperature_air; - this.failsafe = failsafe; - this.wp_num = wp_num; - - } - - /// packet xml order - public static mavlink_high_latency_t PopulateXMLOrder(/*MAV_MODE_FLAG*/byte base_mode,uint custom_mode,/*MAV_LANDED_STATE*/byte landed_state,short roll,short pitch,ushort heading,sbyte throttle,short heading_sp,int latitude,int longitude,short altitude_amsl,short altitude_sp,byte airspeed,byte airspeed_sp,byte groundspeed,sbyte climb_rate,byte gps_nsat,/*GPS_FIX_TYPE*/byte gps_fix_type,byte battery_remaining,sbyte temperature,sbyte temperature_air,byte failsafe,byte wp_num,ushort wp_distance) + public mavlink_camera_tracking_image_status_t(float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y,/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status,/*CAMERA_TRACKING_MODE*/byte tracking_mode,/*CAMERA_TRACKING_TARGET_DATA*/byte target_data) { - var msg = new mavlink_high_latency_t(); - - msg.base_mode = base_mode; - msg.custom_mode = custom_mode; - msg.landed_state = landed_state; - msg.roll = roll; - msg.pitch = pitch; - msg.heading = heading; - msg.throttle = throttle; - msg.heading_sp = heading_sp; - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude_amsl = altitude_amsl; - msg.altitude_sp = altitude_sp; - msg.airspeed = airspeed; - msg.airspeed_sp = airspeed_sp; - msg.groundspeed = groundspeed; - msg.climb_rate = climb_rate; - msg.gps_nsat = gps_nsat; - msg.gps_fix_type = gps_fix_type; - msg.battery_remaining = battery_remaining; - msg.temperature = temperature; - msg.temperature_air = temperature_air; - msg.failsafe = failsafe; - msg.wp_num = wp_num; - msg.wp_distance = wp_distance; + this.point_x = point_x; + this.point_y = point_y; + this.radius = radius; + this.rec_top_x = rec_top_x; + this.rec_top_y = rec_top_y; + this.rec_bottom_x = rec_bottom_x; + this.rec_bottom_y = rec_bottom_y; + this.tracking_status = tracking_status; + this.tracking_mode = tracking_mode; + this.target_data = target_data; + + } + + /// packet xml order + public static mavlink_camera_tracking_image_status_t PopulateXMLOrder(/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status,/*CAMERA_TRACKING_MODE*/byte tracking_mode,/*CAMERA_TRACKING_TARGET_DATA*/byte target_data,float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y) + { + var msg = new mavlink_camera_tracking_image_status_t(); + + msg.tracking_status = tracking_status; + msg.tracking_mode = tracking_mode; + msg.target_data = target_data; + msg.point_x = point_x; + msg.point_y = point_y; + msg.radius = radius; + msg.rec_top_x = rec_top_x; + msg.rec_top_y = rec_top_y; + msg.rec_bottom_x = rec_bottom_x; + msg.rec_bottom_y = rec_bottom_y; return msg; } - /// A bitfield for use for autopilot-specific flags. bitmask + /// Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown [Units("")] - [Description("A bitfield for use for autopilot-specific flags.")] + [Description("Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown")] //[FieldOffset(0)] - public uint custom_mode; + public float point_x; - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] + /// Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown + [Units("")] + [Description("Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown")] //[FieldOffset(4)] - public int latitude; + public float point_y; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] + /// Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown + [Units("")] + [Description("Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown")] //[FieldOffset(8)] - public int longitude; + public float radius; - /// roll [cdeg] - [Units("[cdeg]")] - [Description("roll")] + /// Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown + [Units("")] + [Description("Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown")] //[FieldOffset(12)] - public short roll; - - /// pitch [cdeg] - [Units("[cdeg]")] - [Description("pitch")] - //[FieldOffset(14)] - public short pitch; + public float rec_top_x; - /// heading [cdeg] - [Units("[cdeg]")] - [Description("heading")] + /// Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown + [Units("")] + [Description("Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown")] //[FieldOffset(16)] - public ushort heading; - - /// heading setpoint [cdeg] - [Units("[cdeg]")] - [Description("heading setpoint")] - //[FieldOffset(18)] - public short heading_sp; + public float rec_top_y; - /// Altitude above mean sea level [m] - [Units("[m]")] - [Description("Altitude above mean sea level")] + /// Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown + [Units("")] + [Description("Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown")] //[FieldOffset(20)] - public short altitude_amsl; - - /// Altitude setpoint relative to the home position [m] - [Units("[m]")] - [Description("Altitude setpoint relative to the home position")] - //[FieldOffset(22)] - public short altitude_sp; - - /// distance to target [m] - [Units("[m]")] - [Description("distance to target")] - //[FieldOffset(24)] - public ushort wp_distance; + public float rec_bottom_x; - /// Bitmap of enabled system modes. MAV_MODE_FLAG bitmask + /// Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown [Units("")] - [Description("Bitmap of enabled system modes.")] - //[FieldOffset(26)] - public /*MAV_MODE_FLAG*/byte base_mode; + [Description("Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown")] + //[FieldOffset(24)] + public float rec_bottom_y; - /// The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. MAV_LANDED_STATE + /// Current tracking status CAMERA_TRACKING_STATUS_FLAGS [Units("")] - [Description("The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.")] - //[FieldOffset(27)] - public /*MAV_LANDED_STATE*/byte landed_state; - - /// throttle (percentage) [%] - [Units("[%]")] - [Description("throttle (percentage)")] + [Description("Current tracking status")] //[FieldOffset(28)] - public sbyte throttle; - - /// airspeed [m/s] - [Units("[m/s]")] - [Description("airspeed")] - //[FieldOffset(29)] - public byte airspeed; - - /// airspeed setpoint [m/s] - [Units("[m/s]")] - [Description("airspeed setpoint")] - //[FieldOffset(30)] - public byte airspeed_sp; - - /// groundspeed [m/s] - [Units("[m/s]")] - [Description("groundspeed")] - //[FieldOffset(31)] - public byte groundspeed; - - /// climb rate [m/s] - [Units("[m/s]")] - [Description("climb rate")] - //[FieldOffset(32)] - public sbyte climb_rate; - - /// Number of satellites visible. If unknown, set to 255 - [Units("")] - [Description("Number of satellites visible. If unknown, set to 255")] - //[FieldOffset(33)] - public byte gps_nsat; - - /// GPS Fix type. GPS_FIX_TYPE - [Units("")] - [Description("GPS Fix type.")] - //[FieldOffset(34)] - public /*GPS_FIX_TYPE*/byte gps_fix_type; - - /// Remaining battery (percentage) [%] - [Units("[%]")] - [Description("Remaining battery (percentage)")] - //[FieldOffset(35)] - public byte battery_remaining; - - /// Autopilot temperature (degrees C) [degC] - [Units("[degC]")] - [Description("Autopilot temperature (degrees C)")] - //[FieldOffset(36)] - public sbyte temperature; - - /// Air temperature (degrees C) from airspeed sensor [degC] - [Units("[degC]")] - [Description("Air temperature (degrees C) from airspeed sensor")] - //[FieldOffset(37)] - public sbyte temperature_air; + public /*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status; - /// failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) + /// Current tracking mode CAMERA_TRACKING_MODE [Units("")] - [Description("failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)")] - //[FieldOffset(38)] - public byte failsafe; + [Description("Current tracking mode")] + //[FieldOffset(29)] + public /*CAMERA_TRACKING_MODE*/byte tracking_mode; - /// current waypoint number + /// Defines location of target data CAMERA_TRACKING_TARGET_DATA [Units("")] - [Description("current waypoint number")] - //[FieldOffset(39)] - public byte wp_num; + [Description("Defines location of target data")] + //[FieldOffset(30)] + public /*CAMERA_TRACKING_TARGET_DATA*/byte target_data; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// Message appropriate for high latency connections like Iridium (version 2) - public struct mavlink_high_latency2_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=49)] + /// Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval. + public struct mavlink_camera_tracking_geo_status_t { /// packet ordered constructor - public mavlink_high_latency2_t(uint timestamp,int latitude,int longitude,ushort custom_mode,short altitude,short target_altitude,ushort target_distance,ushort wp_num,/*HL_FAILURE_FLAG*/ushort failure_flags,/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,byte heading,byte target_heading,byte throttle,byte airspeed,byte airspeed_sp,byte groundspeed,byte windspeed,byte wind_heading,byte eph,byte epv,sbyte temperature_air,sbyte climb_rate,sbyte battery,sbyte custom0,sbyte custom1,sbyte custom2) + public mavlink_camera_tracking_geo_status_t(int lat,int lon,float alt,float h_acc,float v_acc,float vel_n,float vel_e,float vel_d,float vel_acc,float dist,float hdg,float hdg_acc,/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status) { - this.timestamp = timestamp; - this.latitude = latitude; - this.longitude = longitude; - this.custom_mode = custom_mode; - this.altitude = altitude; - this.target_altitude = target_altitude; - this.target_distance = target_distance; - this.wp_num = wp_num; - this.failure_flags = failure_flags; - this.type = type; - this.autopilot = autopilot; - this.heading = heading; - this.target_heading = target_heading; - this.throttle = throttle; - this.airspeed = airspeed; - this.airspeed_sp = airspeed_sp; - this.groundspeed = groundspeed; - this.windspeed = windspeed; - this.wind_heading = wind_heading; - this.eph = eph; - this.epv = epv; - this.temperature_air = temperature_air; - this.climb_rate = climb_rate; - this.battery = battery; - this.custom0 = custom0; - this.custom1 = custom1; - this.custom2 = custom2; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.h_acc = h_acc; + this.v_acc = v_acc; + this.vel_n = vel_n; + this.vel_e = vel_e; + this.vel_d = vel_d; + this.vel_acc = vel_acc; + this.dist = dist; + this.hdg = hdg; + this.hdg_acc = hdg_acc; + this.tracking_status = tracking_status; } /// packet xml order - public static mavlink_high_latency2_t PopulateXMLOrder(uint timestamp,/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,ushort custom_mode,int latitude,int longitude,short altitude,short target_altitude,byte heading,byte target_heading,ushort target_distance,byte throttle,byte airspeed,byte airspeed_sp,byte groundspeed,byte windspeed,byte wind_heading,byte eph,byte epv,sbyte temperature_air,sbyte climb_rate,sbyte battery,ushort wp_num,/*HL_FAILURE_FLAG*/ushort failure_flags,sbyte custom0,sbyte custom1,sbyte custom2) + public static mavlink_camera_tracking_geo_status_t PopulateXMLOrder(/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status,int lat,int lon,float alt,float h_acc,float v_acc,float vel_n,float vel_e,float vel_d,float vel_acc,float dist,float hdg,float hdg_acc) { - var msg = new mavlink_high_latency2_t(); + var msg = new mavlink_camera_tracking_geo_status_t(); - msg.timestamp = timestamp; - msg.type = type; - msg.autopilot = autopilot; - msg.custom_mode = custom_mode; - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude = altitude; - msg.target_altitude = target_altitude; - msg.heading = heading; - msg.target_heading = target_heading; - msg.target_distance = target_distance; - msg.throttle = throttle; - msg.airspeed = airspeed; - msg.airspeed_sp = airspeed_sp; - msg.groundspeed = groundspeed; - msg.windspeed = windspeed; - msg.wind_heading = wind_heading; - msg.eph = eph; - msg.epv = epv; - msg.temperature_air = temperature_air; - msg.climb_rate = climb_rate; - msg.battery = battery; - msg.wp_num = wp_num; - msg.failure_flags = failure_flags; - msg.custom0 = custom0; - msg.custom1 = custom1; - msg.custom2 = custom2; + msg.tracking_status = tracking_status; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.h_acc = h_acc; + msg.v_acc = v_acc; + msg.vel_n = vel_n; + msg.vel_e = vel_e; + msg.vel_d = vel_d; + msg.vel_acc = vel_acc; + msg.dist = dist; + msg.hdg = hdg; + msg.hdg_acc = hdg_acc; return msg; } - /// Timestamp (milliseconds since boot or Unix epoch) [ms] - [Units("[ms]")] - [Description("Timestamp (milliseconds since boot or Unix epoch)")] + /// Latitude of tracked object [degE7] + [Units("[degE7]")] + [Description("Latitude of tracked object")] //[FieldOffset(0)] - public uint timestamp; + public int lat; - /// Latitude [degE7] + /// Longitude of tracked object [degE7] [Units("[degE7]")] - [Description("Latitude")] + [Description("Longitude of tracked object")] //[FieldOffset(4)] - public int latitude; + public int lon; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] + /// Altitude of tracked object(AMSL, WGS84) [m] + [Units("[m]")] + [Description("Altitude of tracked object(AMSL, WGS84)")] //[FieldOffset(8)] - public int longitude; - - /// A bitfield for use for autopilot-specific flags (2 byte version). bitmask - [Units("")] - [Description("A bitfield for use for autopilot-specific flags (2 byte version).")] - //[FieldOffset(12)] - public ushort custom_mode; + public float alt; - /// Altitude above mean sea level [m] + /// Horizontal accuracy. NAN if unknown [m] [Units("[m]")] - [Description("Altitude above mean sea level")] - //[FieldOffset(14)] - public short altitude; + [Description("Horizontal accuracy. NAN if unknown")] + //[FieldOffset(12)] + public float h_acc; - /// Altitude setpoint [m] + /// Vertical accuracy. NAN if unknown [m] [Units("[m]")] - [Description("Altitude setpoint")] + [Description("Vertical accuracy. NAN if unknown")] //[FieldOffset(16)] - public short target_altitude; - - /// Distance to target waypoint or position [dam] - [Units("[dam]")] - [Description("Distance to target waypoint or position")] - //[FieldOffset(18)] - public ushort target_distance; + public float v_acc; - /// Current waypoint number - [Units("")] - [Description("Current waypoint number")] + /// North velocity of tracked object. NAN if unknown [m/s] + [Units("[m/s]")] + [Description("North velocity of tracked object. NAN if unknown")] //[FieldOffset(20)] - public ushort wp_num; - - /// Bitmap of failure flags. HL_FAILURE_FLAG bitmask - [Units("")] - [Description("Bitmap of failure flags.")] - //[FieldOffset(22)] - public /*HL_FAILURE_FLAG*/ushort failure_flags; + public float vel_n; - /// Type of the MAV (quadrotor, helicopter, etc.) MAV_TYPE - [Units("")] - [Description("Type of the MAV (quadrotor, helicopter, etc.)")] + /// East velocity of tracked object. NAN if unknown [m/s] + [Units("[m/s]")] + [Description("East velocity of tracked object. NAN if unknown")] //[FieldOffset(24)] - public /*MAV_TYPE*/byte type; - - /// Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. MAV_AUTOPILOT - [Units("")] - [Description("Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.")] - //[FieldOffset(25)] - public /*MAV_AUTOPILOT*/byte autopilot; - - /// Heading [deg/2] - [Units("[deg/2]")] - [Description("Heading")] - //[FieldOffset(26)] - public byte heading; - - /// Heading setpoint [deg/2] - [Units("[deg/2]")] - [Description("Heading setpoint")] - //[FieldOffset(27)] - public byte target_heading; + public float vel_e; - /// Throttle [%] - [Units("[%]")] - [Description("Throttle")] + /// Down velocity of tracked object. NAN if unknown [m/s] + [Units("[m/s]")] + [Description("Down velocity of tracked object. NAN if unknown")] //[FieldOffset(28)] - public byte throttle; + public float vel_d; - /// Airspeed [m/s*5] - [Units("[m/s*5]")] - [Description("Airspeed")] - //[FieldOffset(29)] - public byte airspeed; + /// Velocity accuracy. NAN if unknown [m/s] + [Units("[m/s]")] + [Description("Velocity accuracy. NAN if unknown")] + //[FieldOffset(32)] + public float vel_acc; - /// Airspeed setpoint [m/s*5] - [Units("[m/s*5]")] - [Description("Airspeed setpoint")] - //[FieldOffset(30)] - public byte airspeed_sp; + /// Distance between camera and tracked object. NAN if unknown [m] + [Units("[m]")] + [Description("Distance between camera and tracked object. NAN if unknown")] + //[FieldOffset(36)] + public float dist; - /// Groundspeed [m/s*5] - [Units("[m/s*5]")] - [Description("Groundspeed")] - //[FieldOffset(31)] - public byte groundspeed; + /// Heading in radians, in NED. NAN if unknown [rad] + [Units("[rad]")] + [Description("Heading in radians, in NED. NAN if unknown")] + //[FieldOffset(40)] + public float hdg; - /// Windspeed [m/s*5] - [Units("[m/s*5]")] - [Description("Windspeed")] - //[FieldOffset(32)] - public byte windspeed; + /// Accuracy of heading, in NED. NAN if unknown [rad] + [Units("[rad]")] + [Description("Accuracy of heading, in NED. NAN if unknown")] + //[FieldOffset(44)] + public float hdg_acc; - /// Wind heading [deg/2] - [Units("[deg/2]")] - [Description("Wind heading")] - //[FieldOffset(33)] - public byte wind_heading; + /// Current tracking status CAMERA_TRACKING_STATUS_FLAGS + [Units("")] + [Description("Current tracking status")] + //[FieldOffset(48)] + public /*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status; + }; - /// Maximum error horizontal position since last message [dm] - [Units("[dm]")] - [Description("Maximum error horizontal position since last message")] - //[FieldOffset(34)] - public byte eph; + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] + /// Camera absolute thermal range. This can be streamed when the associated `VIDEO_STREAM_STATUS.flag` bit `VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED` is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras). + public struct mavlink_camera_thermal_range_t + { + /// packet ordered constructor + public mavlink_camera_thermal_range_t(uint time_boot_ms,float max,float max_point_x,float max_point_y,float min,float min_point_x,float min_point_y,byte stream_id,byte camera_device_id) + { + this.time_boot_ms = time_boot_ms; + this.max = max; + this.max_point_x = max_point_x; + this.max_point_y = max_point_y; + this.min = min; + this.min_point_x = min_point_x; + this.min_point_y = min_point_y; + this.stream_id = stream_id; + this.camera_device_id = camera_device_id; + + } + + /// packet xml order + public static mavlink_camera_thermal_range_t PopulateXMLOrder(uint time_boot_ms,byte stream_id,byte camera_device_id,float max,float max_point_x,float max_point_y,float min,float min_point_x,float min_point_y) + { + var msg = new mavlink_camera_thermal_range_t(); - /// Maximum error vertical position since last message [dm] - [Units("[dm]")] - [Description("Maximum error vertical position since last message")] - //[FieldOffset(35)] - public byte epv; + msg.time_boot_ms = time_boot_ms; + msg.stream_id = stream_id; + msg.camera_device_id = camera_device_id; + msg.max = max; + msg.max_point_x = max_point_x; + msg.max_point_y = max_point_y; + msg.min = min; + msg.min_point_x = min_point_x; + msg.min_point_y = min_point_y; + + return msg; + } + - /// Air temperature from airspeed sensor [degC] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; + + /// Temperature max. [degC] [Units("[degC]")] - [Description("Air temperature from airspeed sensor")] - //[FieldOffset(36)] - public sbyte temperature_air; + [Description("Temperature max.")] + //[FieldOffset(4)] + public float max; - /// Maximum climb rate magnitude since last message [dm/s] - [Units("[dm/s]")] - [Description("Maximum climb rate magnitude since last message")] - //[FieldOffset(37)] - public sbyte climb_rate; + /// Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown. + [Units("")] + [Description("Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.")] + //[FieldOffset(8)] + public float max_point_x; - /// Battery level (-1 if field not provided). [%] - [Units("[%]")] - [Description("Battery level (-1 if field not provided).")] - //[FieldOffset(38)] - public sbyte battery; + /// Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown. + [Units("")] + [Description("Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.")] + //[FieldOffset(12)] + public float max_point_y; + + /// Temperature min. [degC] + [Units("[degC]")] + [Description("Temperature min.")] + //[FieldOffset(16)] + public float min; - /// Field for custom payload. + /// Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown. [Units("")] - [Description("Field for custom payload.")] - //[FieldOffset(39)] - public sbyte custom0; + [Description("Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.")] + //[FieldOffset(20)] + public float min_point_x; - /// Field for custom payload. + /// Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown. [Units("")] - [Description("Field for custom payload.")] - //[FieldOffset(40)] - public sbyte custom1; + [Description("Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.")] + //[FieldOffset(24)] + public float min_point_y; - /// Field for custom payload. + /// Video Stream ID (1 for first, 2 for second, etc.) [Units("")] - [Description("Field for custom payload.")] - //[FieldOffset(41)] - public sbyte custom2; + [Description("Video Stream ID (1 for first, 2 for second, etc.)")] + //[FieldOffset(28)] + public byte stream_id; + + /// Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + [Units("")] + [Description("Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id).")] + //[FieldOffset(29)] + public byte camera_device_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - /// Vibration levels and accelerometer clipping - public struct mavlink_vibration_t + [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. + public struct mavlink_gimbal_manager_information_t { /// packet ordered constructor - public mavlink_vibration_t(ulong time_usec,float vibration_x,float vibration_y,float vibration_z,uint clipping_0,uint clipping_1,uint clipping_2) + public mavlink_gimbal_manager_information_t(uint time_boot_ms,/*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,byte gimbal_device_id) { - this.time_usec = time_usec; - this.vibration_x = vibration_x; - this.vibration_y = vibration_y; - this.vibration_z = vibration_z; - this.clipping_0 = clipping_0; - this.clipping_1 = clipping_1; - this.clipping_2 = clipping_2; + this.time_boot_ms = time_boot_ms; + this.cap_flags = cap_flags; + this.roll_min = roll_min; + this.roll_max = roll_max; + this.pitch_min = pitch_min; + this.pitch_max = pitch_max; + this.yaw_min = yaw_min; + this.yaw_max = yaw_max; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_vibration_t PopulateXMLOrder(ulong time_usec,float vibration_x,float vibration_y,float vibration_z,uint clipping_0,uint clipping_1,uint clipping_2) + public static mavlink_gimbal_manager_information_t PopulateXMLOrder(uint time_boot_ms,/*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags,byte gimbal_device_id,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) { - var msg = new mavlink_vibration_t(); + var msg = new mavlink_gimbal_manager_information_t(); - msg.time_usec = time_usec; - msg.vibration_x = vibration_x; - msg.vibration_y = vibration_y; - msg.vibration_z = vibration_z; - msg.clipping_0 = clipping_0; - msg.clipping_1 = clipping_1; - msg.clipping_2 = clipping_2; + msg.time_boot_ms = time_boot_ms; + msg.cap_flags = cap_flags; + msg.gimbal_device_id = gimbal_device_id; + msg.roll_min = roll_min; + msg.roll_max = roll_max; + msg.pitch_min = pitch_min; + msg.pitch_max = pitch_max; + msg.yaw_min = yaw_min; + msg.yaw_max = yaw_max; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ulong time_usec; + public uint time_boot_ms; - /// Vibration levels on X-axis + /// Bitmap of gimbal capability flags. GIMBAL_MANAGER_CAP_FLAGS bitmask [Units("")] - [Description("Vibration levels on X-axis")] + [Description("Bitmap of gimbal capability flags.")] + //[FieldOffset(4)] + public /*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags; + + /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + [Units("[rad]")] + [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] //[FieldOffset(8)] - public float vibration_x; + public float roll_min; - /// Vibration levels on Y-axis - [Units("")] - [Description("Vibration levels on Y-axis")] + /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + [Units("[rad]")] + [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] //[FieldOffset(12)] - public float vibration_y; + public float roll_max; - /// Vibration levels on Z-axis - [Units("")] - [Description("Vibration levels on Z-axis")] + /// Minimum pitch angle (positive: up, negative: down) [rad] + [Units("[rad]")] + [Description("Minimum pitch angle (positive: up, negative: down)")] //[FieldOffset(16)] - public float vibration_z; + public float pitch_min; - /// first accelerometer clipping count - [Units("")] - [Description("first accelerometer clipping count")] + /// Maximum pitch angle (positive: up, negative: down) [rad] + [Units("[rad]")] + [Description("Maximum pitch angle (positive: up, negative: down)")] //[FieldOffset(20)] - public uint clipping_0; + public float pitch_max; - /// second accelerometer clipping count - [Units("")] - [Description("second accelerometer clipping count")] + /// Minimum yaw angle (positive: to the right, negative: to the left) [rad] + [Units("[rad]")] + [Description("Minimum yaw angle (positive: to the right, negative: to the left)")] //[FieldOffset(24)] - public uint clipping_1; + public float yaw_min; - /// third accelerometer clipping count - [Units("")] - [Description("third accelerometer clipping count")] + /// Maximum yaw angle (positive: to the right, negative: to the left) [rad] + [Units("[rad]")] + [Description("Maximum yaw angle (positive: to the right, negative: to the left)")] //[FieldOffset(28)] - public uint clipping_2; + public float yaw_max; + + /// 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. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] + //[FieldOffset(32)] + public byte gimbal_device_id; }; - /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=60)] - /// This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - public struct mavlink_home_position_t + /// 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). + public struct mavlink_gimbal_manager_status_t { /// packet ordered constructor - public mavlink_home_position_t(int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,ulong time_usec) + public mavlink_gimbal_manager_status_t(uint time_boot_ms,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,byte primary_control_sysid,byte primary_control_compid,byte secondary_control_sysid,byte secondary_control_compid) { - this.latitude = latitude; - this.longitude = longitude; - this.altitude = altitude; - this.x = x; - this.y = y; - this.z = z; - this.q = q; - this.approach_x = approach_x; - this.approach_y = approach_y; - this.approach_z = approach_z; - this.time_usec = time_usec; + this.time_boot_ms = time_boot_ms; + this.flags = flags; + this.gimbal_device_id = gimbal_device_id; + this.primary_control_sysid = primary_control_sysid; + this.primary_control_compid = primary_control_compid; + this.secondary_control_sysid = secondary_control_sysid; + this.secondary_control_compid = secondary_control_compid; } /// packet xml order - public static mavlink_home_position_t PopulateXMLOrder(int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,ulong time_usec) + public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,byte primary_control_sysid,byte primary_control_compid,byte secondary_control_sysid,byte secondary_control_compid) { - var msg = new mavlink_home_position_t(); + var msg = new mavlink_gimbal_manager_status_t(); - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude = altitude; - msg.x = x; - msg.y = y; - msg.z = z; - msg.q = q; - msg.approach_x = approach_x; - msg.approach_y = approach_y; - msg.approach_z = approach_z; - msg.time_usec = time_usec; + msg.time_boot_ms = time_boot_ms; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.primary_control_sysid = primary_control_sysid; + msg.primary_control_compid = primary_control_compid; + msg.secondary_control_sysid = secondary_control_sysid; + msg.secondary_control_compid = secondary_control_compid; return msg; } - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public int latitude; + public uint time_boot_ms; - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] + /// High level gimbal manager flags currently applied. GIMBAL_MANAGER_FLAGS bitmask + [Units("")] + [Description("High level gimbal manager flags currently applied.")] //[FieldOffset(4)] - public int longitude; + public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Altitude (MSL). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up.")] + /// 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. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] //[FieldOffset(8)] - public int altitude; + public byte gimbal_device_id; - /// Local X position of this position in the local coordinate frame [m] - [Units("[m]")] - [Description("Local X position of this position in the local coordinate frame")] + /// System ID of MAVLink component with primary control, 0 for none. + [Units("")] + [Description("System ID of MAVLink component with primary control, 0 for none.")] + //[FieldOffset(9)] + public byte primary_control_sysid; + + /// Component ID of MAVLink component with primary control, 0 for none. + [Units("")] + [Description("Component ID of MAVLink component with primary control, 0 for none.")] + //[FieldOffset(10)] + public byte primary_control_compid; + + /// System ID of MAVLink component with secondary control, 0 for none. + [Units("")] + [Description("System ID of MAVLink component with secondary control, 0 for none.")] + //[FieldOffset(11)] + public byte secondary_control_sysid; + + /// Component ID of MAVLink component with secondary control, 0 for none. + [Units("")] + [Description("Component ID of MAVLink component with secondary control, 0 for none.")] //[FieldOffset(12)] - public float x; + public byte secondary_control_compid; + }; - /// Local Y position of this position in the local coordinate frame [m] - [Units("[m]")] - [Description("Local Y position of this position in the local coordinate frame")] - //[FieldOffset(16)] - public float y; + + /// 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 + { + /// 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(); - /// Local Z position of this position in the local coordinate frame [m] - [Units("[m]")] - [Description("Local Z position of this position in the local coordinate frame")] - //[FieldOffset(20)] - public float z; + 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; + } + - /// World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS [Units("")] - [Description("World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground")] - //[FieldOffset(24)] + [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; - /// Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] - [Units("[m]")] - [Description("Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] - //[FieldOffset(40)] - public float approach_x; + /// 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; - /// Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] - [Units("[m]")] - [Description("Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] - //[FieldOffset(44)] - public float approach_y; + /// 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; - /// Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] - [Units("[m]")] - [Description("Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] - //[FieldOffset(48)] - public float approach_z; + /// 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; - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(52)] - public ulong time_usec; + /// 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; }; - [Obsolete] - /// extensions_start 11 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=61)] - /// The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - public struct mavlink_set_home_position_t + + /// 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_set_home_position_t(int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,byte target_system,ulong time_usec) + 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.latitude = latitude; - this.longitude = longitude; - this.altitude = altitude; - this.x = x; - this.y = y; - this.z = z; - this.q = q; - this.approach_x = approach_x; - this.approach_y = approach_y; - this.approach_z = approach_z; - this.target_system = target_system; - this.time_usec = time_usec; + this.uid = uid; + this.time_boot_ms = time_boot_ms; + this.firmware_version = firmware_version; + this.hardware_version = hardware_version; + this.roll_min = roll_min; + this.roll_max = roll_max; + this.pitch_min = pitch_min; + this.pitch_max = pitch_max; + this.yaw_min = yaw_min; + this.yaw_max = yaw_max; + this.cap_flags = cap_flags; + this.custom_cap_flags = custom_cap_flags; + 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_set_home_position_t PopulateXMLOrder(byte target_system,int latitude,int longitude,int altitude,float x,float y,float z,float[] q,float approach_x,float approach_y,float approach_z,ulong time_usec) + 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_set_home_position_t(); + var msg = new mavlink_gimbal_device_information_t(); - msg.target_system = target_system; - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude = altitude; - msg.x = x; - msg.y = y; - msg.z = z; - msg.q = q; - msg.approach_x = approach_x; - msg.approach_y = approach_y; - msg.approach_z = approach_z; - msg.time_usec = time_usec; + msg.time_boot_ms = time_boot_ms; + msg.vendor_name = vendor_name; + msg.model_name = model_name; + msg.custom_name = custom_name; + msg.firmware_version = firmware_version; + msg.hardware_version = hardware_version; + msg.uid = uid; + msg.cap_flags = cap_flags; + msg.custom_cap_flags = custom_cap_flags; + msg.roll_min = roll_min; + msg.roll_max = roll_max; + msg.pitch_min = pitch_min; + msg.pitch_max = pitch_max; + msg.yaw_min = yaw_min; + msg.yaw_max = yaw_max; + msg.gimbal_device_id = gimbal_device_id; return msg; } - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] + /// UID of gimbal hardware (0 if unknown). + [Units("")] + [Description("UID of gimbal hardware (0 if unknown).")] //[FieldOffset(0)] - public int latitude; - - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] - //[FieldOffset(4)] - public int longitude; + public ulong uid; - /// Altitude (MSL). Positive for up. [mm] - [Units("[mm]")] - [Description("Altitude (MSL). Positive for up.")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(8)] - public int altitude; + public uint time_boot_ms; - /// Local X position of this position in the local coordinate frame [m] - [Units("[m]")] - [Description("Local X position of this position in the local coordinate frame")] + /// Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). + [Units("")] + [Description("Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).")] //[FieldOffset(12)] - public float x; + public uint firmware_version; - /// Local Y position of this position in the local coordinate frame [m] - [Units("[m]")] - [Description("Local Y position of this position in the local coordinate frame")] + /// Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). + [Units("")] + [Description("Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).")] //[FieldOffset(16)] - public float y; + public uint hardware_version; - /// Local Z position of this position in the local coordinate frame [m] - [Units("[m]")] - [Description("Local Z position of this position in the local coordinate frame")] + /// 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). NAN if unknown.")] //[FieldOffset(20)] - public float z; + public float roll_min; - /// World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - [Units("")] - [Description("World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground")] + /// 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). NAN if unknown.")] //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] - [Units("[m]")] - [Description("Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] - //[FieldOffset(40)] - public float approach_x; - - /// Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] - [Units("[m]")] - [Description("Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] - //[FieldOffset(44)] - public float approach_y; - - /// Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. [m] - [Units("[m]")] - [Description("Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.")] - //[FieldOffset(48)] - public float approach_z; + public float roll_max; - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(52)] - public byte target_system; + /// Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] + [Units("[rad]")] + [Description("Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] + //[FieldOffset(28)] + public float pitch_min; - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(53)] - public ulong time_usec; - }; + /// Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] + [Units("[rad]")] + [Description("Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] + //[FieldOffset(32)] + public float pitch_max; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - /// The interval between messages for a particular MAVLink message ID. This message is the response to the MAV_CMD_GET_MESSAGE_INTERVAL command. This interface replaces DATA_STREAM. - public struct mavlink_message_interval_t - { - /// packet ordered constructor - public mavlink_message_interval_t(int interval_us,ushort message_id) - { - this.interval_us = interval_us; - this.message_id = message_id; - - } - - /// packet xml order - public static mavlink_message_interval_t PopulateXMLOrder(ushort message_id,int interval_us) - { - var msg = new mavlink_message_interval_t(); + /// 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). NAN if unknown.")] + //[FieldOffset(36)] + public float yaw_min; - msg.message_id = message_id; - msg.interval_us = interval_us; - - return msg; - } - + /// 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). NAN if unknown.")] + //[FieldOffset(40)] + public float yaw_max; - /// The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. [us] - [Units("[us]")] - [Description("The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.")] - //[FieldOffset(0)] - public int interval_us; + /// Bitmap of gimbal capability flags. GIMBAL_DEVICE_CAP_FLAGS bitmask + [Units("")] + [Description("Bitmap of gimbal capability flags.")] + //[FieldOffset(44)] + public /*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags; - /// The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + /// Bitmap for use for gimbal-specific capability flags. bitmask [Units("")] - [Description("The ID of the requested MAVLink message. v1.0 is limited to 254 messages.")] - //[FieldOffset(4)] - public ushort message_id; - }; + [Description("Bitmap for use for gimbal-specific capability flags.")] + //[FieldOffset(46)] + public ushort custom_cap_flags; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Provides state for additional features - public struct mavlink_extended_sys_state_t - { - /// packet ordered constructor - public mavlink_extended_sys_state_t(/*MAV_VTOL_STATE*/byte vtol_state,/*MAV_LANDED_STATE*/byte landed_state) - { - this.vtol_state = vtol_state; - this.landed_state = landed_state; - - } - - /// packet xml order - public static mavlink_extended_sys_state_t PopulateXMLOrder(/*MAV_VTOL_STATE*/byte vtol_state,/*MAV_LANDED_STATE*/byte landed_state) - { - var msg = new mavlink_extended_sys_state_t(); + /// Name of the gimbal vendor. + [Units("")] + [Description("Name of the gimbal vendor.")] + //[FieldOffset(48)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] vendor_name; - msg.vtol_state = vtol_state; - msg.landed_state = landed_state; - - return msg; - } - + /// Name of the gimbal model. + [Units("")] + [Description("Name of the gimbal model.")] + //[FieldOffset(80)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] model_name; - /// The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. MAV_VTOL_STATE + /// Custom name of the gimbal given to it by the user. [Units("")] - [Description("The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.")] - //[FieldOffset(0)] - public /*MAV_VTOL_STATE*/byte vtol_state; + [Description("Custom name of the gimbal given to it by the user.")] + //[FieldOffset(112)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] custom_name; - /// The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. MAV_LANDED_STATE + /// 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("The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.")] - //[FieldOffset(1)] - public /*MAV_LANDED_STATE*/byte landed_state; + [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; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=38)] - /// The location and information of an ADSB vehicle - public struct mavlink_adsb_vehicle_t + [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. 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 - public mavlink_adsb_vehicle_t(uint ICAO_address,int lat,int lon,int altitude,ushort heading,ushort hor_velocity,short ver_velocity,/*ADSB_FLAGS*/ushort flags,ushort squawk,/*ADSB_ALTITUDE_TYPE*/byte altitude_type,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitter_type,byte tslc) + public mavlink_gimbal_device_set_attitude_t(float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component) { - this.ICAO_address = ICAO_address; - this.lat = lat; - this.lon = lon; - this.altitude = altitude; - this.heading = heading; - this.hor_velocity = hor_velocity; - this.ver_velocity = ver_velocity; + 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.flags = flags; - this.squawk = squawk; - this.altitude_type = altitude_type; - this.callsign = callsign; - this.emitter_type = emitter_type; - this.tslc = tslc; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_adsb_vehicle_t PopulateXMLOrder(uint ICAO_address,int lat,int lon,/*ADSB_ALTITUDE_TYPE*/byte altitude_type,int altitude,ushort heading,ushort hor_velocity,short ver_velocity,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitter_type,byte tslc,/*ADSB_FLAGS*/ushort flags,ushort squawk) + public static mavlink_gimbal_device_set_attitude_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) { - var msg = new mavlink_adsb_vehicle_t(); + var msg = new mavlink_gimbal_device_set_attitude_t(); - msg.ICAO_address = ICAO_address; - msg.lat = lat; - msg.lon = lon; - msg.altitude_type = altitude_type; - msg.altitude = altitude; - msg.heading = heading; - msg.hor_velocity = hor_velocity; - msg.ver_velocity = ver_velocity; - msg.callsign = callsign; - msg.emitter_type = emitter_type; - msg.tslc = tslc; + msg.target_system = target_system; + msg.target_component = target_component; msg.flags = flags; - msg.squawk = squawk; + 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; } - /// ICAO address + /// 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("ICAO address")] + [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)] - public uint ICAO_address; - - /// Latitude [degE7] - [Units("[degE7]")] - [Description("Latitude")] - //[FieldOffset(4)] - public int lat; - - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] - //[FieldOffset(8)] - public int lon; - - /// Altitude(ASL) [mm] - [Units("[mm]")] - [Description("Altitude(ASL)")] - //[FieldOffset(12)] - public int altitude; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Course over ground [cdeg] - [Units("[cdeg]")] - [Description("Course over ground")] + /// 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: rolling to the right). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(16)] - public ushort heading; - - /// The horizontal velocity [cm/s] - [Units("[cm/s]")] - [Description("The horizontal velocity")] - //[FieldOffset(18)] - public ushort hor_velocity; + public float angular_velocity_x; - /// The vertical velocity. Positive is up [cm/s] - [Units("[cm/s]")] - [Description("The vertical velocity. Positive is up")] + /// 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: pitching up). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(20)] - public short ver_velocity; - - /// Bitmap to indicate various statuses including valid data fields ADSB_FLAGS bitmask - [Units("")] - [Description("Bitmap to indicate various statuses including valid data fields")] - //[FieldOffset(22)] - public /*ADSB_FLAGS*/ushort flags; + public float angular_velocity_y; - /// Squawk code - [Units("")] - [Description("Squawk code")] + /// 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: yawing to the right). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(24)] - public ushort squawk; + public float angular_velocity_z; - /// ADSB altitude type. ADSB_ALTITUDE_TYPE + /// Low level gimbal flags. GIMBAL_DEVICE_FLAGS bitmask [Units("")] - [Description("ADSB altitude type.")] - //[FieldOffset(26)] - public /*ADSB_ALTITUDE_TYPE*/byte altitude_type; + [Description("Low level gimbal flags.")] + //[FieldOffset(28)] + public /*GIMBAL_DEVICE_FLAGS*/ushort flags; - /// The callsign, 8+null + /// System ID [Units("")] - [Description("The callsign, 8+null")] - //[FieldOffset(27)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] - public byte[] callsign; + [Description("System ID")] + //[FieldOffset(30)] + public byte target_system; - /// ADSB emitter type. ADSB_EMITTER_TYPE + /// Component ID [Units("")] - [Description("ADSB emitter type.")] - //[FieldOffset(36)] - public /*ADSB_EMITTER_TYPE*/byte emitter_type; - - /// Time since last communication in seconds [s] - [Units("[s]")] - [Description("Time since last communication in seconds")] - //[FieldOffset(37)] - public byte tslc; + [Description("Component ID")] + //[FieldOffset(31)] + public byte target_component; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] - /// Information about a potential collision - public struct mavlink_collision_t + /// 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_collision_t(uint id,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta,/*MAV_COLLISION_SRC*/byte src,/*MAV_COLLISION_ACTION*/byte action,/*MAV_COLLISION_THREAT_LEVEL*/byte threat_level) + 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.id = id; - this.time_to_minimum_delta = time_to_minimum_delta; - this.altitude_minimum_delta = altitude_minimum_delta; - this.horizontal_minimum_delta = horizontal_minimum_delta; - this.src = src; - this.action = action; - this.threat_level = threat_level; + this.time_boot_ms = time_boot_ms; + 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.failure_flags = failure_flags; + 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_collision_t PopulateXMLOrder(/*MAV_COLLISION_SRC*/byte src,uint id,/*MAV_COLLISION_ACTION*/byte action,/*MAV_COLLISION_THREAT_LEVEL*/byte threat_level,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta) + 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_collision_t(); + var msg = new mavlink_gimbal_device_attitude_status_t(); - msg.src = src; - msg.id = id; - msg.action = action; - msg.threat_level = threat_level; - msg.time_to_minimum_delta = time_to_minimum_delta; - msg.altitude_minimum_delta = altitude_minimum_delta; - msg.horizontal_minimum_delta = horizontal_minimum_delta; + msg.target_system = target_system; + msg.target_component = target_component; + msg.time_boot_ms = time_boot_ms; + msg.flags = flags; + 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.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; } - /// Unique identifier, domain based on src field - [Units("")] - [Description("Unique identifier, domain based on src field")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public uint id; + public uint time_boot_ms; - /// Estimated time until collision occurs [s] - [Units("[s]")] - [Description("Estimated time until collision occurs")] + /// 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 described in the message description.")] //[FieldOffset(4)] - public float time_to_minimum_delta; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Closest vertical distance between vehicle and object [m] - [Units("[m]")] - [Description("Closest vertical distance between vehicle and object")] - //[FieldOffset(8)] - public float altitude_minimum_delta; + /// 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 (positive: rolling to the right). The frame is described in the message description. NaN if unknown.")] + //[FieldOffset(20)] + public float angular_velocity_x; - /// Closest horizontal distance between vehicle and object [m] - [Units("[m]")] - [Description("Closest horizontal distance between vehicle and object")] - //[FieldOffset(12)] - public float horizontal_minimum_delta; + /// 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 (positive: pitching up). The frame is described in the message description. NaN if unknown.")] + //[FieldOffset(24)] + public float angular_velocity_y; - /// Collision data source MAV_COLLISION_SRC + /// 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 (positive: yawing to the right). The frame is described in the message description. NaN if unknown.")] + //[FieldOffset(28)] + public float angular_velocity_z; + + /// Failure flags (0 for no failure) GIMBAL_DEVICE_ERROR_FLAGS bitmask [Units("")] - [Description("Collision data source")] - //[FieldOffset(16)] - public /*MAV_COLLISION_SRC*/byte src; + [Description("Failure flags (0 for no failure)")] + //[FieldOffset(32)] + public /*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags; - /// Action that is being taken to avoid this collision MAV_COLLISION_ACTION + /// Current gimbal flags set. GIMBAL_DEVICE_FLAGS bitmask [Units("")] - [Description("Action that is being taken to avoid this collision")] - //[FieldOffset(17)] - public /*MAV_COLLISION_ACTION*/byte action; + [Description("Current gimbal flags set.")] + //[FieldOffset(36)] + public /*GIMBAL_DEVICE_FLAGS*/ushort flags; - /// How concerned the aircraft is about this collision MAV_COLLISION_THREAT_LEVEL + /// System ID [Units("")] - [Description("How concerned the aircraft is about this collision")] - //[FieldOffset(18)] - public /*MAV_COLLISION_THREAT_LEVEL*/byte threat_level; + [Description("System ID")] + //[FieldOffset(38)] + public byte target_system; + + /// Component ID + [Units("")] + [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=254)] - /// Message implementing parts of the V2 payload specs in V1 frames for transitional support. - public struct mavlink_v2_extension_t + /// 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_v2_extension_t(ushort message_type,byte target_network,byte target_system,byte target_component,byte[] payload) + 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.message_type = message_type; - this.target_network = target_network; + this.time_boot_us = time_boot_us; + this.q = q; + this.q_estimated_delay_us = q_estimated_delay_us; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.v_estimated_delay_us = v_estimated_delay_us; + this.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; + this.estimator_status = estimator_status; this.target_system = target_system; this.target_component = target_component; - this.payload = payload; + this.landed_state = landed_state; + this.angular_velocity_z = angular_velocity_z; } /// packet xml order - public static mavlink_v2_extension_t PopulateXMLOrder(byte target_network,byte target_system,byte target_component,ushort message_type,byte[] payload) + 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_v2_extension_t(); + var msg = new mavlink_autopilot_state_for_gimbal_device_t(); - msg.target_network = target_network; msg.target_system = target_system; msg.target_component = target_component; - msg.message_type = message_type; - msg.payload = payload; + msg.time_boot_us = time_boot_us; + msg.q = q; + msg.q_estimated_delay_us = q_estimated_delay_us; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.v_estimated_delay_us = v_estimated_delay_us; + 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; } - /// A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - [Units("")] - [Description("A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.")] + /// Timestamp (time since system boot). [us] + [Units("[us]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public ushort message_type; + public ulong time_boot_us; - /// Network ID (0 for broadcast) + /// Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). [Units("")] - [Description("Network ID (0 for broadcast)")] - //[FieldOffset(2)] - public byte target_network; + [Description("Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// System ID (0 for broadcast) + /// Estimated delay of the attitude data. 0 if unknown. [us] + [Units("[us]")] + [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). NAN if unknown. [m/s] + [Units("[m/s]")] + [Description("X Speed in NED (North, East, Down). NAN if unknown.")] + //[FieldOffset(28)] + public float vx; + + /// Y Speed in NED (North, East, Down). NAN if unknown. [m/s] + [Units("[m/s]")] + [Description("Y Speed in NED (North, East, Down). NAN if unknown.")] + //[FieldOffset(32)] + public float vy; + + /// Z Speed in NED (North, East, Down). NAN if unknown. [m/s] + [Units("[m/s]")] + [Description("Z Speed in NED (North, East, Down). NAN if unknown.")] + //[FieldOffset(36)] + public float vz; + + /// Estimated delay of the speed data. 0 if unknown. [us] + [Units("[us]")] + [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: 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: 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; + + /// Bitmap indicating which estimator outputs are valid. ESTIMATOR_STATUS_FLAGS bitmask [Units("")] - [Description("System ID (0 for broadcast)")] - //[FieldOffset(3)] + [Description("Bitmap indicating which estimator outputs are valid.")] + //[FieldOffset(48)] + public /*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(50)] public byte target_system; - /// Component ID (0 for broadcast) + /// Component ID [Units("")] - [Description("Component ID (0 for broadcast)")] - //[FieldOffset(4)] + [Description("Component ID")] + //[FieldOffset(51)] public byte target_component; - /// Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. - [Units("")] - [Description("Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification.")] - //[FieldOffset(5)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=249)] - public byte[] payload; + /// The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. MAV_LANDED_STATE + [Units("")] + [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; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)] - /// Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - public struct mavlink_memory_vect_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_memory_vect_t(ushort address,byte ver,byte type,sbyte[] value) + 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.address = address; - this.ver = ver; - this.type = type; - this.value = value; + this.flags = flags; + 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; } /// packet xml order - public static mavlink_memory_vect_t PopulateXMLOrder(ushort address,byte ver,byte type,sbyte[] value) + 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_memory_vect_t(); + var msg = new mavlink_gimbal_manager_set_pitchyaw_t(); - msg.address = address; - msg.ver = ver; - msg.type = type; - msg.value = value; + msg.target_system = target_system; + msg.target_component = target_component; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.pitch = pitch; + msg.yaw = yaw; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; return msg; } - /// Starting address of the debug variables + /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS [Units("")] - [Description("Starting address of the debug variables")] + [Description("High level gimbal manager flags to use.")] //[FieldOffset(0)] - public ushort address; + public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + /// 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)] + 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).")] + //[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).")] + //[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).")] + //[FieldOffset(16)] + public float yaw_rate; + + /// System ID [Units("")] - [Description("Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below")] - //[FieldOffset(2)] - public byte ver; + [Description("System ID")] + //[FieldOffset(20)] + public byte target_system; - /// Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + /// Component ID [Units("")] - [Description("Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14")] - //[FieldOffset(3)] - public byte type; + [Description("Component ID")] + //[FieldOffset(21)] + public byte target_component; - /// Memory contents at specified address + /// 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("Memory contents at specified address")] - //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public sbyte[] value; + [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(22)] + public byte gimbal_device_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] - /// To debug something using a named 3D vector. - public struct mavlink_debug_vect_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] + /// 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_debug_vect_t(ulong time_usec,float x,float y,float z,byte[] name) + 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.time_usec = time_usec; - this.x = x; - this.y = y; - this.z = z; - this.name = name; + this.flags = flags; + 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; } /// packet xml order - public static mavlink_debug_vect_t PopulateXMLOrder(byte[] name,ulong time_usec,float x,float y,float z) + 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_debug_vect_t(); + var msg = new mavlink_gimbal_manager_set_manual_control_t(); - msg.name = name; - msg.time_usec = time_usec; - msg.x = x; - msg.y = y; - msg.z = z; + msg.target_system = target_system; + msg.target_component = target_component; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.pitch = pitch; + msg.yaw = yaw; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// High level gimbal manager flags. GIMBAL_MANAGER_FLAGS + [Units("")] + [Description("High level gimbal manager flags.")] //[FieldOffset(0)] - public ulong time_usec; + public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// x + /// Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). [Units("")] - [Description("x")] + [Description("Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).")] + //[FieldOffset(4)] + public float pitch; + + /// 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 x; + public float yaw; - /// y + /// Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). [Units("")] - [Description("y")] + [Description("Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).")] //[FieldOffset(12)] - public float y; + public float pitch_rate; - /// z + /// Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). [Units("")] - [Description("z")] + [Description("Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).")] //[FieldOffset(16)] - public float z; + public float yaw_rate; - /// Name + /// System ID [Units("")] - [Description("Name")] + [Description("System ID")] //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[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(22)] + public byte gimbal_device_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - /// Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - public struct mavlink_named_value_float_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=96)] + /// Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE + public struct mavlink_wifi_config_ap_t { /// packet ordered constructor - public mavlink_named_value_float_t(uint time_boot_ms,float value,byte[] name) + public mavlink_wifi_config_ap_t(byte[] ssid,byte[] password) { - this.time_boot_ms = time_boot_ms; - this.value = value; - this.name = name; + this.ssid = ssid; + this.password = password; } /// packet xml order - public static mavlink_named_value_float_t PopulateXMLOrder(uint time_boot_ms,byte[] name,float value) + public static mavlink_wifi_config_ap_t PopulateXMLOrder(byte[] ssid,byte[] password) { - var msg = new mavlink_named_value_float_t(); + var msg = new mavlink_wifi_config_ap_t(); - msg.time_boot_ms = time_boot_ms; - msg.name = name; - msg.value = value; + msg.ssid = ssid; + msg.password = password; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// Floating point value + /// Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. [Units("")] - [Description("Floating point value")] - //[FieldOffset(4)] - public float value; + [Description("Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] ssid; - /// Name of the debug variable + /// Password. Blank for an open AP. MD5 hash when message is sent back as a response. [Units("")] - [Description("Name of the debug variable")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; + [Description("Password. Blank for an open AP. MD5 hash when message is sent back as a response.")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=64)] + public byte[] password; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - /// Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - public struct mavlink_named_value_int_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=58)] + /// The location and information of an AIS vessel + public struct mavlink_ais_vessel_t { /// packet ordered constructor - public mavlink_named_value_int_t(uint time_boot_ms,int value,byte[] name) + public mavlink_ais_vessel_t(uint MMSI,int lat,int lon,ushort COG,ushort heading,ushort velocity,ushort dimension_bow,ushort dimension_stern,ushort tslc,/*AIS_FLAGS*/ushort flags,sbyte turn_rate,/*AIS_NAV_STATUS*/byte navigational_status,/*AIS_TYPE*/byte type,byte dimension_port,byte dimension_starboard,byte[] callsign,byte[] name) { - this.time_boot_ms = time_boot_ms; - this.value = value; + this.MMSI = MMSI; + this.lat = lat; + this.lon = lon; + this.COG = COG; + this.heading = heading; + this.velocity = velocity; + this.dimension_bow = dimension_bow; + this.dimension_stern = dimension_stern; + this.tslc = tslc; + this.flags = flags; + this.turn_rate = turn_rate; + this.navigational_status = navigational_status; + this.type = type; + this.dimension_port = dimension_port; + this.dimension_starboard = dimension_starboard; + this.callsign = callsign; this.name = name; } /// packet xml order - public static mavlink_named_value_int_t PopulateXMLOrder(uint time_boot_ms,byte[] name,int value) + public static mavlink_ais_vessel_t PopulateXMLOrder(uint MMSI,int lat,int lon,ushort COG,ushort heading,ushort velocity,sbyte turn_rate,/*AIS_NAV_STATUS*/byte navigational_status,/*AIS_TYPE*/byte type,ushort dimension_bow,ushort dimension_stern,byte dimension_port,byte dimension_starboard,byte[] callsign,byte[] name,ushort tslc,/*AIS_FLAGS*/ushort flags) { - var msg = new mavlink_named_value_int_t(); + var msg = new mavlink_ais_vessel_t(); - msg.time_boot_ms = time_boot_ms; + msg.MMSI = MMSI; + msg.lat = lat; + msg.lon = lon; + msg.COG = COG; + msg.heading = heading; + msg.velocity = velocity; + msg.turn_rate = turn_rate; + msg.navigational_status = navigational_status; + msg.type = type; + msg.dimension_bow = dimension_bow; + msg.dimension_stern = dimension_stern; + msg.dimension_port = dimension_port; + msg.dimension_starboard = dimension_starboard; + msg.callsign = callsign; msg.name = name; - msg.value = value; + msg.tslc = tslc; + msg.flags = flags; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Mobile Marine Service Identifier, 9 decimal digits + [Units("")] + [Description("Mobile Marine Service Identifier, 9 decimal digits")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint MMSI; - /// Signed integer value - [Units("")] - [Description("Signed integer value")] + /// Latitude [degE7] + [Units("[degE7]")] + [Description("Latitude")] //[FieldOffset(4)] - public int value; + public int lat; - /// Name of the debug variable - [Units("")] - [Description("Name of the debug variable")] + /// Longitude [degE7] + [Units("[degE7]")] + [Description("Longitude")] //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; - }; + public int lon; - - /// extensions_start 2 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] - /// Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). - public struct mavlink_statustext_t - { - /// packet ordered constructor - public mavlink_statustext_t(/*MAV_SEVERITY*/byte severity,byte[] text,ushort id,byte chunk_seq) - { - this.severity = severity; - this.text = text; - this.id = id; - this.chunk_seq = chunk_seq; - - } - - /// packet xml order - public static mavlink_statustext_t PopulateXMLOrder(/*MAV_SEVERITY*/byte severity,byte[] text,ushort id,byte chunk_seq) - { - var msg = new mavlink_statustext_t(); + /// Course over ground [cdeg] + [Units("[cdeg]")] + [Description("Course over ground")] + //[FieldOffset(12)] + public ushort COG; - msg.severity = severity; - msg.text = text; - msg.id = id; - msg.chunk_seq = chunk_seq; - - return msg; - } - + /// True heading [cdeg] + [Units("[cdeg]")] + [Description("True heading")] + //[FieldOffset(14)] + public ushort heading; - /// Severity of status. Relies on the definitions within RFC-5424. MAV_SEVERITY + /// Speed over ground [cm/s] + [Units("[cm/s]")] + [Description("Speed over ground")] + //[FieldOffset(16)] + public ushort velocity; + + /// Distance from lat/lon location to bow [m] + [Units("[m]")] + [Description("Distance from lat/lon location to bow")] + //[FieldOffset(18)] + public ushort dimension_bow; + + /// Distance from lat/lon location to stern [m] + [Units("[m]")] + [Description("Distance from lat/lon location to stern")] + //[FieldOffset(20)] + public ushort dimension_stern; + + /// Time since last communication in seconds [s] + [Units("[s]")] + [Description("Time since last communication in seconds")] + //[FieldOffset(22)] + public ushort tslc; + + /// Bitmask to indicate various statuses including valid data fields AIS_FLAGS bitmask [Units("")] - [Description("Severity of status. Relies on the definitions within RFC-5424.")] - //[FieldOffset(0)] - public /*MAV_SEVERITY*/byte severity; + [Description("Bitmask to indicate various statuses including valid data fields")] + //[FieldOffset(24)] + public /*AIS_FLAGS*/ushort flags; - /// Status text message, without null termination character + /// Turn rate [cdeg/s] + [Units("[cdeg/s]")] + [Description("Turn rate")] + //[FieldOffset(26)] + public sbyte turn_rate; + + /// Navigational status AIS_NAV_STATUS [Units("")] - [Description("Status text message, without null termination character")] - //[FieldOffset(1)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] - public byte[] text; + [Description("Navigational status")] + //[FieldOffset(27)] + public /*AIS_NAV_STATUS*/byte navigational_status; - /// Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. + /// Type of vessels AIS_TYPE [Units("")] - [Description("Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.")] - //[FieldOffset(51)] - public ushort id; + [Description("Type of vessels")] + //[FieldOffset(28)] + public /*AIS_TYPE*/byte type; - /// This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. + /// Distance from lat/lon location to port side [m] + [Units("[m]")] + [Description("Distance from lat/lon location to port side")] + //[FieldOffset(29)] + public byte dimension_port; + + /// Distance from lat/lon location to starboard side [m] + [Units("[m]")] + [Description("Distance from lat/lon location to starboard side")] + //[FieldOffset(30)] + public byte dimension_starboard; + + /// The vessel callsign [Units("")] - [Description("This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.")] - //[FieldOffset(53)] - public byte chunk_seq; + [Description("The vessel callsign")] + //[FieldOffset(31)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=7)] + public byte[] callsign; + + /// The vessel name + [Units("")] + [Description("The vessel name")] + //[FieldOffset(38)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] name; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. - public struct mavlink_debug_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] + /// General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message 'uavcan.protocol.NodeStatus' for the background information. The UAVCAN specification is available at http://uavcan.org. + public struct mavlink_uavcan_node_status_t { /// packet ordered constructor - public mavlink_debug_t(uint time_boot_ms,float value,byte ind) + public mavlink_uavcan_node_status_t(ulong time_usec,uint uptime_sec,ushort vendor_specific_status_code,/*UAVCAN_NODE_HEALTH*/byte health,/*UAVCAN_NODE_MODE*/byte mode,byte sub_mode) { - this.time_boot_ms = time_boot_ms; - this.value = value; - this.ind = ind; + this.time_usec = time_usec; + this.uptime_sec = uptime_sec; + this.vendor_specific_status_code = vendor_specific_status_code; + this.health = health; + this.mode = mode; + this.sub_mode = sub_mode; } /// packet xml order - public static mavlink_debug_t PopulateXMLOrder(uint time_boot_ms,byte ind,float value) + public static mavlink_uavcan_node_status_t PopulateXMLOrder(ulong time_usec,uint uptime_sec,/*UAVCAN_NODE_HEALTH*/byte health,/*UAVCAN_NODE_MODE*/byte mode,byte sub_mode,ushort vendor_specific_status_code) { - var msg = new mavlink_debug_t(); + var msg = new mavlink_uavcan_node_status_t(); - msg.time_boot_ms = time_boot_ms; - msg.ind = ind; - msg.value = value; + msg.time_usec = time_usec; + msg.uptime_sec = uptime_sec; + msg.health = health; + msg.mode = mode; + msg.sub_mode = sub_mode; + msg.vendor_specific_status_code = vendor_specific_status_code; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint time_boot_ms; + public ulong time_usec; - /// DEBUG value + /// Time since the start-up of the node. [s] + [Units("[s]")] + [Description("Time since the start-up of the node.")] + //[FieldOffset(8)] + public uint uptime_sec; + + /// Vendor-specific status information. [Units("")] - [Description("DEBUG value")] - //[FieldOffset(4)] - public float value; + [Description("Vendor-specific status information.")] + //[FieldOffset(12)] + public ushort vendor_specific_status_code; - /// index of debug variable + /// Generalized node health status. UAVCAN_NODE_HEALTH [Units("")] - [Description("index of debug variable")] - //[FieldOffset(8)] - public byte ind; + [Description("Generalized node health status.")] + //[FieldOffset(14)] + public /*UAVCAN_NODE_HEALTH*/byte health; + + /// Generalized operating mode. UAVCAN_NODE_MODE + [Units("")] + [Description("Generalized operating mode.")] + //[FieldOffset(15)] + public /*UAVCAN_NODE_MODE*/byte mode; + + /// Not used currently. + [Units("")] + [Description("Not used currently.")] + //[FieldOffset(16)] + public byte sub_mode; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing - public struct mavlink_setup_signing_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=116)] + /// General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service 'uavcan.protocol.GetNodeInfo' for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at http://uavcan.org. + public struct mavlink_uavcan_node_info_t { /// packet ordered constructor - public mavlink_setup_signing_t(ulong initial_timestamp,byte target_system,byte target_component,byte[] secret_key) + public mavlink_uavcan_node_info_t(ulong time_usec,uint uptime_sec,uint sw_vcs_commit,byte[] name,byte hw_version_major,byte hw_version_minor,byte[] hw_unique_id,byte sw_version_major,byte sw_version_minor) { - this.initial_timestamp = initial_timestamp; - this.target_system = target_system; - this.target_component = target_component; - this.secret_key = secret_key; + this.time_usec = time_usec; + this.uptime_sec = uptime_sec; + this.sw_vcs_commit = sw_vcs_commit; + this.name = name; + this.hw_version_major = hw_version_major; + this.hw_version_minor = hw_version_minor; + this.hw_unique_id = hw_unique_id; + this.sw_version_major = sw_version_major; + this.sw_version_minor = sw_version_minor; } /// packet xml order - public static mavlink_setup_signing_t PopulateXMLOrder(byte target_system,byte target_component,byte[] secret_key,ulong initial_timestamp) + public static mavlink_uavcan_node_info_t PopulateXMLOrder(ulong time_usec,uint uptime_sec,byte[] name,byte hw_version_major,byte hw_version_minor,byte[] hw_unique_id,byte sw_version_major,byte sw_version_minor,uint sw_vcs_commit) { - var msg = new mavlink_setup_signing_t(); + var msg = new mavlink_uavcan_node_info_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.secret_key = secret_key; - msg.initial_timestamp = initial_timestamp; + msg.time_usec = time_usec; + msg.uptime_sec = uptime_sec; + msg.name = name; + msg.hw_version_major = hw_version_major; + msg.hw_version_minor = hw_version_minor; + msg.hw_unique_id = hw_unique_id; + msg.sw_version_major = sw_version_major; + msg.sw_version_minor = sw_version_minor; + msg.sw_vcs_commit = sw_vcs_commit; return msg; } - /// initial timestamp - [Units("")] - [Description("initial timestamp")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public ulong initial_timestamp; + public ulong time_usec; - /// system id of the target - [Units("")] - [Description("system id of the target")] + /// Time since the start-up of the node. [s] + [Units("[s]")] + [Description("Time since the start-up of the node.")] //[FieldOffset(8)] - public byte target_system; + public uint uptime_sec; - /// component ID of the target + /// Version control system (VCS) revision identifier (e.g. git short commit hash). Zero if unknown. [Units("")] - [Description("component ID of the target")] - //[FieldOffset(9)] - public byte target_component; + [Description("Version control system (VCS) revision identifier (e.g. git short commit hash). Zero if unknown.")] + //[FieldOffset(12)] + public uint sw_vcs_commit; - /// signing key + /// Node name string. For example, 'sapog.px4.io'. [Units("")] - [Description("signing key")] - //[FieldOffset(10)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] secret_key; + [Description("Node name string. For example, 'sapog.px4.io'.")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=80)] + public byte[] name; + + /// Hardware major version number. + [Units("")] + [Description("Hardware major version number.")] + //[FieldOffset(96)] + public byte hw_version_major; + + /// Hardware minor version number. + [Units("")] + [Description("Hardware minor version number.")] + //[FieldOffset(97)] + public byte hw_version_minor; + + /// Hardware unique 128-bit ID. + [Units("")] + [Description("Hardware unique 128-bit ID.")] + //[FieldOffset(98)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] hw_unique_id; + + /// Software major version number. + [Units("")] + [Description("Software major version number.")] + //[FieldOffset(114)] + public byte sw_version_major; + + /// Software minor version number. + [Units("")] + [Description("Software minor version number.")] + //[FieldOffset(115)] + public byte sw_version_minor; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Report button state change. - public struct mavlink_button_change_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response. + public struct mavlink_param_ext_request_read_t { /// packet ordered constructor - public mavlink_button_change_t(uint time_boot_ms,uint last_change_ms,byte state) + public mavlink_param_ext_request_read_t(short param_index,byte target_system,byte target_component,byte[] param_id) { - this.time_boot_ms = time_boot_ms; - this.last_change_ms = last_change_ms; - this.state = state; + this.param_index = param_index; + this.target_system = target_system; + this.target_component = target_component; + this.param_id = param_id; } /// packet xml order - public static mavlink_button_change_t PopulateXMLOrder(uint time_boot_ms,uint last_change_ms,byte state) + public static mavlink_param_ext_request_read_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,short param_index) { - var msg = new mavlink_button_change_t(); + var msg = new mavlink_param_ext_request_read_t(); - msg.time_boot_ms = time_boot_ms; - msg.last_change_ms = last_change_ms; - msg.state = state; + msg.target_system = target_system; + msg.target_component = target_component; + msg.param_id = param_id; + msg.param_index = param_index; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) + [Units("")] + [Description("Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)")] //[FieldOffset(0)] - public uint time_boot_ms; + public short param_index; - /// Time of last change of button state. [ms] - [Units("[ms]")] - [Description("Time of last change of button state.")] - //[FieldOffset(4)] - public uint last_change_ms; + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(2)] + public byte target_system; - /// Bitmap for state of buttons. bitmask + /// Component ID [Units("")] - [Description("Bitmap for state of buttons.")] - //[FieldOffset(8)] - public byte state; + [Description("Component ID")] + //[FieldOffset(3)] + public byte target_component; + + /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + [Units("")] + [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; }; - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=232)] - /// Control vehicle tone generation (buzzer). - public struct mavlink_play_tune_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE. + public struct mavlink_param_ext_request_list_t { /// packet ordered constructor - public mavlink_play_tune_t(byte target_system,byte target_component,byte[] tune,byte[] tune2) + public mavlink_param_ext_request_list_t(byte target_system,byte target_component) { this.target_system = target_system; this.target_component = target_component; - this.tune = tune; - this.tune2 = tune2; } /// packet xml order - public static mavlink_play_tune_t PopulateXMLOrder(byte target_system,byte target_component,byte[] tune,byte[] tune2) + public static mavlink_param_ext_request_list_t PopulateXMLOrder(byte target_system,byte target_component) { - var msg = new mavlink_play_tune_t(); + var msg = new mavlink_param_ext_request_list_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.tune = tune; - msg.tune2 = tune2; return msg; } @@ -25257,1413 +30868,1387 @@ public static mavlink_play_tune_t PopulateXMLOrder(byte target_system,byte targe [Description("Component ID")] //[FieldOffset(1)] public byte target_component; - - /// tune in board specific format - [Units("")] - [Description("tune in board specific format")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=30)] - public byte[] tune; - - /// tune extension (appended to tune) - [Units("")] - [Description("tune extension (appended to tune)")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=200)] - public byte[] tune2; }; - /// 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 + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=149)] + /// Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout. + public struct mavlink_param_ext_value_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,byte gimbal_device_id) + public mavlink_param_ext_value_t(ushort param_count,ushort param_index,byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type) { - this.time_boot_ms = time_boot_ms; - this.firmware_version = firmware_version; - this.focal_length = focal_length; - this.sensor_size_h = sensor_size_h; - this.sensor_size_v = sensor_size_v; - this.flags = flags; - this.resolution_h = resolution_h; - this.resolution_v = resolution_v; - this.cam_definition_version = cam_definition_version; - this.vendor_name = vendor_name; - this.model_name = model_name; - this.lens_id = lens_id; - this.cam_definition_uri = cam_definition_uri; - this.gimbal_device_id = gimbal_device_id; + this.param_count = param_count; + this.param_index = param_index; + this.param_id = param_id; + this.param_value = param_value; + this.param_type = param_type; } /// 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,byte gimbal_device_id) + public static mavlink_param_ext_value_t PopulateXMLOrder(byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type,ushort param_count,ushort param_index) { - var msg = new mavlink_camera_information_t(); + var msg = new mavlink_param_ext_value_t(); - msg.time_boot_ms = time_boot_ms; - msg.vendor_name = vendor_name; - msg.model_name = model_name; - msg.firmware_version = firmware_version; - msg.focal_length = focal_length; - msg.sensor_size_h = sensor_size_h; - msg.sensor_size_v = sensor_size_v; - msg.resolution_h = resolution_h; - msg.resolution_v = resolution_v; - msg.lens_id = lens_id; - msg.flags = flags; - msg.cam_definition_version = cam_definition_version; - msg.cam_definition_uri = cam_definition_uri; - msg.gimbal_device_id = gimbal_device_id; + msg.param_id = param_id; + msg.param_value = param_value; + msg.param_type = param_type; + msg.param_count = param_count; + msg.param_index = param_index; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. - [Units("")] - [Description("Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.")] - //[FieldOffset(4)] - public uint firmware_version; - - /// Focal length. Use NaN if not known. [mm] - [Units("[mm]")] - [Description("Focal length. Use NaN if not known.")] - //[FieldOffset(8)] - public float focal_length; - - /// Image sensor size horizontal. Use NaN if not known. [mm] - [Units("[mm]")] - [Description("Image sensor size horizontal. Use NaN if not known.")] - //[FieldOffset(12)] - public float sensor_size_h; - - /// Image sensor size vertical. Use NaN if not known. [mm] - [Units("[mm]")] - [Description("Image sensor size vertical. Use NaN if not known.")] - //[FieldOffset(16)] - public float sensor_size_v; - - /// Bitmap of camera capability flags. CAMERA_CAP_FLAGS bitmask - [Units("")] - [Description("Bitmap of camera capability flags.")] - //[FieldOffset(20)] - public /*CAMERA_CAP_FLAGS*/uint flags; - - /// Horizontal image resolution. Use 0 if not known. [pix] - [Units("[pix]")] - [Description("Horizontal image resolution. Use 0 if not known.")] - //[FieldOffset(24)] - public ushort resolution_h; - - /// Vertical image resolution. Use 0 if not known. [pix] - [Units("[pix]")] - [Description("Vertical image resolution. Use 0 if not known.")] - //[FieldOffset(26)] - public ushort resolution_v; - - /// Camera definition version (iteration). Use 0 if not known. - [Units("")] - [Description("Camera definition version (iteration). Use 0 if not known.")] - //[FieldOffset(28)] - public ushort cam_definition_version; - - /// Name of the camera vendor + /// Total number of parameters [Units("")] - [Description("Name of the camera vendor")] - //[FieldOffset(30)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] vendor_name; + [Description("Total number of parameters")] + //[FieldOffset(0)] + public ushort param_count; - /// Name of the camera model + /// Index of this parameter [Units("")] - [Description("Name of the camera model")] - //[FieldOffset(62)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] model_name; + [Description("Index of this parameter")] + //[FieldOffset(2)] + public ushort param_index; - /// Reserved for a lens ID. Use 0 if not known. + /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string [Units("")] - [Description("Reserved for a lens ID. Use 0 if not known.")] - //[FieldOffset(94)] - public byte lens_id; + [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; - /// 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. + /// Parameter value [Units("")] - [Description("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.")] - //[FieldOffset(95)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=140)] - public byte[] cam_definition_uri; + [Description("Parameter value")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] + public byte[] param_value; - /// 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. + /// Parameter type. MAV_PARAM_EXT_TYPE [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; + [Description("Parameter type.")] + //[FieldOffset(148)] + public /*MAV_PARAM_EXT_TYPE*/byte param_type; }; - /// extensions_start 2 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] - /// Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - public struct mavlink_camera_settings_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=147)] + /// Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response. + public struct mavlink_param_ext_set_t { /// packet ordered constructor - public mavlink_camera_settings_t(uint time_boot_ms,/*CAMERA_MODE*/byte mode_id,float zoomLevel,float focusLevel) + public mavlink_param_ext_set_t(byte target_system,byte target_component,byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type) { - this.time_boot_ms = time_boot_ms; - this.mode_id = mode_id; - this.zoomLevel = zoomLevel; - this.focusLevel = focusLevel; + this.target_system = target_system; + this.target_component = target_component; + this.param_id = param_id; + this.param_value = param_value; + this.param_type = param_type; } /// packet xml order - public static mavlink_camera_settings_t PopulateXMLOrder(uint time_boot_ms,/*CAMERA_MODE*/byte mode_id,float zoomLevel,float focusLevel) + public static mavlink_param_ext_set_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type) { - var msg = new mavlink_camera_settings_t(); + var msg = new mavlink_param_ext_set_t(); - msg.time_boot_ms = time_boot_ms; - msg.mode_id = mode_id; - msg.zoomLevel = zoomLevel; - msg.focusLevel = focusLevel; + msg.target_system = target_system; + msg.target_component = target_component; + msg.param_id = param_id; + msg.param_value = param_value; + msg.param_type = param_type; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// System ID + [Units("")] + [Description("System ID")] //[FieldOffset(0)] - public uint time_boot_ms; + public byte target_system; - /// Camera mode CAMERA_MODE + /// Component ID [Units("")] - [Description("Camera mode")] - //[FieldOffset(4)] - public /*CAMERA_MODE*/byte mode_id; + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; - /// Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) + /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string [Units("")] - [Description("Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)")] - //[FieldOffset(5)] - public float zoomLevel; + [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; - /// Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) + /// Parameter value [Units("")] - [Description("Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)")] - //[FieldOffset(9)] - public float focusLevel; + [Description("Parameter value")] + //[FieldOffset(18)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] + public byte[] param_value; + + /// Parameter type. MAV_PARAM_EXT_TYPE + [Units("")] + [Description("Parameter type.")] + //[FieldOffset(146)] + public /*MAV_PARAM_EXT_TYPE*/byte param_type; }; - /// extensions_start 9 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=60)] - /// Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc. - public struct mavlink_storage_information_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=146)] + /// Response from a PARAM_EXT_SET message. + public struct mavlink_param_ext_ack_t { /// packet ordered constructor - public mavlink_storage_information_t(uint time_boot_ms,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed,byte storage_id,byte storage_count,/*STORAGE_STATUS*/byte status,/*STORAGE_TYPE*/byte type,byte[] name) + public mavlink_param_ext_ack_t(byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type,/*PARAM_ACK*/byte param_result) { - this.time_boot_ms = time_boot_ms; - this.total_capacity = total_capacity; - this.used_capacity = used_capacity; - this.available_capacity = available_capacity; - this.read_speed = read_speed; - this.write_speed = write_speed; - this.storage_id = storage_id; - this.storage_count = storage_count; - this.status = status; - this.type = type; - this.name = name; + this.param_id = param_id; + this.param_value = param_value; + this.param_type = param_type; + this.param_result = param_result; } /// packet xml order - public static mavlink_storage_information_t PopulateXMLOrder(uint time_boot_ms,byte storage_id,byte storage_count,/*STORAGE_STATUS*/byte status,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed,/*STORAGE_TYPE*/byte type,byte[] name) + public static mavlink_param_ext_ack_t PopulateXMLOrder(byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type,/*PARAM_ACK*/byte param_result) { - var msg = new mavlink_storage_information_t(); + var msg = new mavlink_param_ext_ack_t(); - msg.time_boot_ms = time_boot_ms; - msg.storage_id = storage_id; - msg.storage_count = storage_count; - msg.status = status; - msg.total_capacity = total_capacity; - msg.used_capacity = used_capacity; - msg.available_capacity = available_capacity; - msg.read_speed = read_speed; - msg.write_speed = write_speed; - msg.type = type; - msg.name = name; + msg.param_id = param_id; + msg.param_value = param_value; + msg.param_type = param_type; + msg.param_result = param_result; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(0)] - public uint time_boot_ms; - - /// Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. [MiB] - [Units("[MiB]")] - [Description("Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.")] - //[FieldOffset(4)] - public float total_capacity; - - /// Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. [MiB] - [Units("[MiB]")] - [Description("Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.")] - //[FieldOffset(8)] - public float used_capacity; - - /// Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. [MiB] - [Units("[MiB]")] - [Description("Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.")] - //[FieldOffset(12)] - public float available_capacity; - - /// Read speed. [MiB/s] - [Units("[MiB/s]")] - [Description("Read speed.")] - //[FieldOffset(16)] - public float read_speed; - - /// Write speed. [MiB/s] - [Units("[MiB/s]")] - [Description("Write speed.")] - //[FieldOffset(20)] - public float write_speed; - - /// Storage ID (1 for first, 2 for second, etc.) - [Units("")] - [Description("Storage ID (1 for first, 2 for second, etc.)")] - //[FieldOffset(24)] - public byte storage_id; - - /// Number of storage devices + /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string [Units("")] - [Description("Number of storage devices")] - //[FieldOffset(25)] - public byte storage_count; + [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] param_id; - /// Status of storage STORAGE_STATUS - [Units("")] - [Description("Status of storage")] - //[FieldOffset(26)] - public /*STORAGE_STATUS*/byte status; + /// Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) + [Units("")] + [Description("Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] + public byte[] param_value; - /// Type of storage STORAGE_TYPE + /// Parameter type. MAV_PARAM_EXT_TYPE [Units("")] - [Description("Type of storage")] - //[FieldOffset(27)] - public /*STORAGE_TYPE*/byte type; + [Description("Parameter type.")] + //[FieldOffset(144)] + public /*MAV_PARAM_EXT_TYPE*/byte param_type; - /// Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. + /// Result code. PARAM_ACK [Units("")] - [Description("Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.")] - //[FieldOffset(28)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] name; + [Description("Result code.")] + //[FieldOffset(145)] + public /*PARAM_ACK*/byte param_result; }; /// extensions_start 6 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - /// Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - public struct mavlink_camera_capture_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=167)] + /// Obstacle distances in front of the sensor, starting from the left in increment degrees to the right + public struct mavlink_obstacle_distance_t { /// packet ordered constructor - public mavlink_camera_capture_status_t(uint time_boot_ms,float image_interval,uint recording_time_ms,float available_capacity,byte image_status,byte video_status,int image_count) + public mavlink_obstacle_distance_t(ulong time_usec,ushort[] distances,ushort min_distance,ushort max_distance,/*MAV_DISTANCE_SENSOR*/byte sensor_type,byte increment,float increment_f,float angle_offset,/*MAV_FRAME*/byte frame) { - this.time_boot_ms = time_boot_ms; - this.image_interval = image_interval; - this.recording_time_ms = recording_time_ms; - this.available_capacity = available_capacity; - this.image_status = image_status; - this.video_status = video_status; - this.image_count = image_count; + this.time_usec = time_usec; + this.distances = distances; + this.min_distance = min_distance; + this.max_distance = max_distance; + this.sensor_type = sensor_type; + this.increment = increment; + this.increment_f = increment_f; + this.angle_offset = angle_offset; + this.frame = frame; } /// packet xml order - public static mavlink_camera_capture_status_t PopulateXMLOrder(uint time_boot_ms,byte image_status,byte video_status,float image_interval,uint recording_time_ms,float available_capacity,int image_count) + public static mavlink_obstacle_distance_t PopulateXMLOrder(ulong time_usec,/*MAV_DISTANCE_SENSOR*/byte sensor_type,ushort[] distances,byte increment,ushort min_distance,ushort max_distance,float increment_f,float angle_offset,/*MAV_FRAME*/byte frame) { - var msg = new mavlink_camera_capture_status_t(); + var msg = new mavlink_obstacle_distance_t(); - msg.time_boot_ms = time_boot_ms; - msg.image_status = image_status; - msg.video_status = video_status; - msg.image_interval = image_interval; - msg.recording_time_ms = recording_time_ms; - msg.available_capacity = available_capacity; - msg.image_count = image_count; + msg.time_usec = time_usec; + msg.sensor_type = sensor_type; + msg.distances = distances; + msg.increment = increment; + msg.min_distance = min_distance; + msg.max_distance = max_distance; + msg.increment_f = increment_f; + msg.angle_offset = angle_offset; + msg.frame = frame; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint time_boot_ms; - - /// Image capture interval [s] - [Units("[s]")] - [Description("Image capture interval")] - //[FieldOffset(4)] - public float image_interval; + public ulong time_usec; - /// Time since recording started [ms] - [Units("[ms]")] - [Description("Time since recording started")] + /// Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. [cm] + [Units("[cm]")] + [Description("Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.")] //[FieldOffset(8)] - public uint recording_time_ms; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=72)] + public ushort[] distances; - /// Available storage capacity. [MiB] - [Units("[MiB]")] - [Description("Available storage capacity.")] - //[FieldOffset(12)] - public float available_capacity; + /// Minimum distance the sensor can measure. [cm] + [Units("[cm]")] + [Description("Minimum distance the sensor can measure.")] + //[FieldOffset(152)] + public ushort min_distance; - /// Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) - [Units("")] - [Description("Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)")] - //[FieldOffset(16)] - public byte image_status; + /// Maximum distance the sensor can measure. [cm] + [Units("[cm]")] + [Description("Maximum distance the sensor can measure.")] + //[FieldOffset(154)] + public ushort max_distance; - /// Current status of video capturing (0: idle, 1: capture in progress) + /// Class id of the distance sensor type. MAV_DISTANCE_SENSOR [Units("")] - [Description("Current status of video capturing (0: idle, 1: capture in progress)")] - //[FieldOffset(17)] - public byte video_status; + [Description("Class id of the distance sensor type.")] + //[FieldOffset(156)] + public /*MAV_DISTANCE_SENSOR*/byte sensor_type; - /// Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). + /// Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. [deg] + [Units("[deg]")] + [Description("Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.")] + //[FieldOffset(157)] + public byte increment; + + /// Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. [deg] + [Units("[deg]")] + [Description("Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.")] + //[FieldOffset(158)] + public float increment_f; + + /// Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. [deg] + [Units("[deg]")] + [Description("Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.")] + //[FieldOffset(162)] + public float angle_offset; + + /// Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. MAV_FRAME [Units("")] - [Description("Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).")] - //[FieldOffset(18)] - public int image_count; + [Description("Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.")] + //[FieldOffset(166)] + public /*MAV_FRAME*/byte frame; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] - /// Information about a captured image. This is emitted every time a message is captured. It may be re-requested using MAV_CMD_REQUEST_MESSAGE, using param2 to indicate the sequence number for the missing image. - public struct mavlink_camera_image_captured_t + /// extensions_start 15 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=233)] + /// Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html). + public struct mavlink_odometry_t { /// packet ordered constructor - public mavlink_camera_image_captured_t(ulong time_utc,uint time_boot_ms,int lat,int lon,int alt,int relative_alt,float[] q,int image_index,byte camera_id,sbyte capture_result,byte[] file_url) + public mavlink_odometry_t(ulong time_usec,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,sbyte quality) { - this.time_utc = time_utc; - this.time_boot_ms = time_boot_ms; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.relative_alt = relative_alt; + this.time_usec = time_usec; + this.x = x; + this.y = y; + this.z = z; this.q = q; - this.image_index = image_index; - this.camera_id = camera_id; - this.capture_result = capture_result; - this.file_url = file_url; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.rollspeed = rollspeed; + this.pitchspeed = pitchspeed; + this.yawspeed = yawspeed; + this.pose_covariance = pose_covariance; + this.velocity_covariance = velocity_covariance; + this.frame_id = frame_id; + this.child_frame_id = child_frame_id; + this.reset_counter = reset_counter; + this.estimator_type = estimator_type; + this.quality = quality; } /// packet xml order - public static mavlink_camera_image_captured_t PopulateXMLOrder(uint time_boot_ms,ulong time_utc,byte camera_id,int lat,int lon,int alt,int relative_alt,float[] q,int image_index,sbyte capture_result,byte[] file_url) + public static mavlink_odometry_t PopulateXMLOrder(ulong time_usec,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,sbyte quality) { - var msg = new mavlink_camera_image_captured_t(); + var msg = new mavlink_odometry_t(); - msg.time_boot_ms = time_boot_ms; - msg.time_utc = time_utc; - msg.camera_id = camera_id; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.relative_alt = relative_alt; + msg.time_usec = time_usec; + msg.frame_id = frame_id; + msg.child_frame_id = child_frame_id; + msg.x = x; + msg.y = y; + msg.z = z; msg.q = q; - msg.image_index = image_index; - msg.capture_result = capture_result; - msg.file_url = file_url; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.rollspeed = rollspeed; + msg.pitchspeed = pitchspeed; + msg.yawspeed = yawspeed; + msg.pose_covariance = pose_covariance; + msg.velocity_covariance = velocity_covariance; + msg.reset_counter = reset_counter; + msg.estimator_type = estimator_type; + msg.quality = quality; return msg; } - /// Timestamp (time since UNIX epoch) in UTC. 0 for unknown. [us] + /// 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. [us] [Units("[us]")] - [Description("Timestamp (time since UNIX epoch) in UTC. 0 for unknown.")] + [Description("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.")] //[FieldOffset(0)] - public ulong time_utc; + public ulong time_usec; - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// X Position [m] + [Units("[m]")] + [Description("X Position")] //[FieldOffset(8)] - public uint time_boot_ms; + public float x; - /// Latitude where image was taken [degE7] - [Units("[degE7]")] - [Description("Latitude where image was taken")] + /// Y Position [m] + [Units("[m]")] + [Description("Y Position")] //[FieldOffset(12)] - public int lat; + public float y; - /// Longitude where capture was taken [degE7] - [Units("[degE7]")] - [Description("Longitude where capture was taken")] + /// Z Position [m] + [Units("[m]")] + [Description("Z Position")] //[FieldOffset(16)] - public int lon; - - /// Altitude (MSL) where image was taken [mm] - [Units("[mm]")] - [Description("Altitude (MSL) where image was taken")] - //[FieldOffset(20)] - public int alt; - - /// Altitude above ground [mm] - [Units("[mm]")] - [Description("Altitude above ground")] - //[FieldOffset(24)] - public int relative_alt; + public float z; - /// Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) [Units("")] - [Description("Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] - //[FieldOffset(28)] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)")] + //[FieldOffset(20)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) - [Units("")] - [Description("Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)")] + /// X linear speed [m/s] + [Units("[m/s]")] + [Description("X linear speed")] + //[FieldOffset(36)] + public float vx; + + /// Y linear speed [m/s] + [Units("[m/s]")] + [Description("Y linear speed")] + //[FieldOffset(40)] + public float vy; + + /// Z linear speed [m/s] + [Units("[m/s]")] + [Description("Z linear speed")] //[FieldOffset(44)] - public int image_index; + public float vz; - /// Deprecated/unused. Component IDs are used to differentiate multiple cameras. - [Units("")] - [Description("Deprecated/unused. Component IDs are used to differentiate multiple cameras.")] + /// Roll angular speed [rad/s] + [Units("[rad/s]")] + [Description("Roll angular speed")] //[FieldOffset(48)] - public byte camera_id; + public float rollspeed; - /// Boolean indicating success (1) or failure (0) while capturing this image. - [Units("")] - [Description("Boolean indicating success (1) or failure (0) while capturing this image.")] - //[FieldOffset(49)] - public sbyte capture_result; + /// Pitch angular speed [rad/s] + [Units("[rad/s]")] + [Description("Pitch angular speed")] + //[FieldOffset(52)] + public float pitchspeed; - /// URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. + /// Yaw angular speed [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular speed")] + //[FieldOffset(56)] + public float yawspeed; + + /// Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. [Units("")] - [Description("URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.")] - //[FieldOffset(50)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=205)] - public byte[] file_url; - }; + [Description("Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(60)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] + public float[] pose_covariance; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - /// Information about flight since last arming. - public struct mavlink_flight_information_t - { - /// packet ordered constructor - public mavlink_flight_information_t(ulong arming_time_utc,ulong takeoff_time_utc,ulong flight_uuid,uint time_boot_ms) - { - this.arming_time_utc = arming_time_utc; - this.takeoff_time_utc = takeoff_time_utc; - this.flight_uuid = flight_uuid; - this.time_boot_ms = time_boot_ms; - - } - - /// packet xml order - public static mavlink_flight_information_t PopulateXMLOrder(uint time_boot_ms,ulong arming_time_utc,ulong takeoff_time_utc,ulong flight_uuid) - { - var msg = new mavlink_flight_information_t(); + /// Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. + [Units("")] + [Description("Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] + //[FieldOffset(144)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] + public float[] velocity_covariance; - msg.time_boot_ms = time_boot_ms; - msg.arming_time_utc = arming_time_utc; - msg.takeoff_time_utc = takeoff_time_utc; - msg.flight_uuid = flight_uuid; - - return msg; - } - + /// Coordinate frame of reference for the pose data. MAV_FRAME + [Units("")] + [Description("Coordinate frame of reference for the pose data.")] + //[FieldOffset(228)] + public /*MAV_FRAME*/byte frame_id; - /// Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown [us] - [Units("[us]")] - [Description("Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown")] - //[FieldOffset(0)] - public ulong arming_time_utc; + /// Coordinate frame of reference for the velocity in free space (twist) data. MAV_FRAME + [Units("")] + [Description("Coordinate frame of reference for the velocity in free space (twist) data.")] + //[FieldOffset(229)] + public /*MAV_FRAME*/byte child_frame_id; - /// Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown [us] - [Units("[us]")] - [Description("Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown")] - //[FieldOffset(8)] - public ulong takeoff_time_utc; + /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. + [Units("")] + [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] + //[FieldOffset(230)] + public byte reset_counter; - /// Universally unique identifier (UUID) of flight, should correspond to name of log files + /// Type of estimator that is providing the odometry. MAV_ESTIMATOR_TYPE [Units("")] - [Description("Universally unique identifier (UUID) of flight, should correspond to name of log files")] - //[FieldOffset(16)] - public ulong flight_uuid; + [Description("Type of estimator that is providing the odometry.")] + //[FieldOffset(231)] + public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(24)] - public uint time_boot_ms; + /// Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality [%] + [Units("[%]")] + [Description("Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality")] + //[FieldOffset(232)] + public sbyte quality; }; - /// extensions_start 4 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Orientation of a mount - public struct mavlink_mount_orientation_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=239)] + /// Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED). + public struct mavlink_trajectory_representation_waypoints_t { /// packet ordered constructor - public mavlink_mount_orientation_t(uint time_boot_ms,float roll,float pitch,float yaw,float yaw_absolute) + public mavlink_trajectory_representation_waypoints_t(ulong time_usec,float[] pos_x,float[] pos_y,float[] pos_z,float[] vel_x,float[] vel_y,float[] vel_z,float[] acc_x,float[] acc_y,float[] acc_z,float[] pos_yaw,float[] vel_yaw,ushort[] command,byte valid_points) { - this.time_boot_ms = time_boot_ms; - this.roll = roll; - this.pitch = pitch; - this.yaw = yaw; - this.yaw_absolute = yaw_absolute; + this.time_usec = time_usec; + this.pos_x = pos_x; + this.pos_y = pos_y; + this.pos_z = pos_z; + this.vel_x = vel_x; + this.vel_y = vel_y; + this.vel_z = vel_z; + this.acc_x = acc_x; + this.acc_y = acc_y; + this.acc_z = acc_z; + this.pos_yaw = pos_yaw; + this.vel_yaw = vel_yaw; + this.command = command; + this.valid_points = valid_points; } /// packet xml order - public static mavlink_mount_orientation_t PopulateXMLOrder(uint time_boot_ms,float roll,float pitch,float yaw,float yaw_absolute) + public static mavlink_trajectory_representation_waypoints_t PopulateXMLOrder(ulong time_usec,byte valid_points,float[] pos_x,float[] pos_y,float[] pos_z,float[] vel_x,float[] vel_y,float[] vel_z,float[] acc_x,float[] acc_y,float[] acc_z,float[] pos_yaw,float[] vel_yaw,ushort[] command) { - var msg = new mavlink_mount_orientation_t(); + var msg = new mavlink_trajectory_representation_waypoints_t(); - msg.time_boot_ms = time_boot_ms; - msg.roll = roll; - msg.pitch = pitch; - msg.yaw = yaw; - msg.yaw_absolute = yaw_absolute; + msg.time_usec = time_usec; + msg.valid_points = valid_points; + msg.pos_x = pos_x; + msg.pos_y = pos_y; + msg.pos_z = pos_z; + msg.vel_x = vel_x; + msg.vel_y = vel_y; + msg.vel_z = vel_z; + msg.acc_x = acc_x; + msg.acc_y = acc_y; + msg.acc_z = acc_z; + msg.pos_yaw = pos_yaw; + msg.vel_yaw = vel_yaw; + msg.command = command; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint time_boot_ms; - - /// Roll in global frame (set to NaN for invalid). [deg] - [Units("[deg]")] - [Description("Roll in global frame (set to NaN for invalid).")] - //[FieldOffset(4)] - public float roll; + public ulong time_usec; - /// Pitch in global frame (set to NaN for invalid). [deg] - [Units("[deg]")] - [Description("Pitch in global frame (set to NaN for invalid).")] + /// X-coordinate of waypoint, set to NaN if not being used [m] + [Units("[m]")] + [Description("X-coordinate of waypoint, set to NaN if not being used")] //[FieldOffset(8)] - public float pitch; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_x; - /// Yaw relative to vehicle (set to NaN for invalid). [deg] - [Units("[deg]")] - [Description("Yaw relative to vehicle (set to NaN for invalid).")] - //[FieldOffset(12)] - public float yaw; + /// Y-coordinate of waypoint, set to NaN if not being used [m] + [Units("[m]")] + [Description("Y-coordinate of waypoint, set to NaN if not being used")] + //[FieldOffset(28)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_y; - /// Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). [deg] - [Units("[deg]")] - [Description("Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).")] - //[FieldOffset(16)] - public float yaw_absolute; - }; + /// Z-coordinate of waypoint, set to NaN if not being used [m] + [Units("[m]")] + [Description("Z-coordinate of waypoint, set to NaN if not being used")] + //[FieldOffset(48)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_z; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] - /// A message containing logged data (see also MAV_CMD_LOGGING_START) - public struct mavlink_logging_data_t - { - /// packet ordered constructor - public mavlink_logging_data_t(ushort sequence,byte target_system,byte target_component,byte length,byte first_message_offset,byte[] data) - { - this.sequence = sequence; - this.target_system = target_system; - this.target_component = target_component; - this.length = length; - this.first_message_offset = first_message_offset; - this.data = data; - - } - - /// packet xml order - public static mavlink_logging_data_t PopulateXMLOrder(byte target_system,byte target_component,ushort sequence,byte length,byte first_message_offset,byte[] data) - { - var msg = new mavlink_logging_data_t(); + /// X-velocity of waypoint, set to NaN if not being used [m/s] + [Units("[m/s]")] + [Description("X-velocity of waypoint, set to NaN if not being used")] + //[FieldOffset(68)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] vel_x; - msg.target_system = target_system; - msg.target_component = target_component; - msg.sequence = sequence; - msg.length = length; - msg.first_message_offset = first_message_offset; - msg.data = data; - - return msg; - } - + /// Y-velocity of waypoint, set to NaN if not being used [m/s] + [Units("[m/s]")] + [Description("Y-velocity of waypoint, set to NaN if not being used")] + //[FieldOffset(88)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] vel_y; - /// sequence number (can wrap) - [Units("")] - [Description("sequence number (can wrap)")] - //[FieldOffset(0)] - public ushort sequence; + /// Z-velocity of waypoint, set to NaN if not being used [m/s] + [Units("[m/s]")] + [Description("Z-velocity of waypoint, set to NaN if not being used")] + //[FieldOffset(108)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] vel_z; - /// system ID of the target - [Units("")] - [Description("system ID of the target")] - //[FieldOffset(2)] - public byte target_system; + /// X-acceleration of waypoint, set to NaN if not being used [m/s/s] + [Units("[m/s/s]")] + [Description("X-acceleration of waypoint, set to NaN if not being used")] + //[FieldOffset(128)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] acc_x; - /// component ID of the target - [Units("")] - [Description("component ID of the target")] - //[FieldOffset(3)] - public byte target_component; + /// Y-acceleration of waypoint, set to NaN if not being used [m/s/s] + [Units("[m/s/s]")] + [Description("Y-acceleration of waypoint, set to NaN if not being used")] + //[FieldOffset(148)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] acc_y; - /// data length [bytes] - [Units("[bytes]")] - [Description("data length")] - //[FieldOffset(4)] - public byte length; + /// Z-acceleration of waypoint, set to NaN if not being used [m/s/s] + [Units("[m/s/s]")] + [Description("Z-acceleration of waypoint, set to NaN if not being used")] + //[FieldOffset(168)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] acc_z; + + /// Yaw angle, set to NaN if not being used [rad] + [Units("[rad]")] + [Description("Yaw angle, set to NaN if not being used")] + //[FieldOffset(188)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_yaw; + + /// Yaw rate, set to NaN if not being used [rad/s] + [Units("[rad/s]")] + [Description("Yaw rate, set to NaN if not being used")] + //[FieldOffset(208)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] vel_yaw; - /// offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). [bytes] - [Units("[bytes]")] - [Description("offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).")] - //[FieldOffset(5)] - public byte first_message_offset; + /// MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. MAV_CMD + [Units("")] + [Description("MAV_CMD command id of waypoint, set to UINT16_MAX if not being used.")] + //[FieldOffset(228)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public ushort[] command; - /// logged data + /// Number of valid points (up-to 5 waypoints are possible) [Units("")] - [Description("logged data")] - //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=249)] - public byte[] data; + [Description("Number of valid points (up-to 5 waypoints are possible)")] + //[FieldOffset(238)] + public byte valid_points; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=255)] - /// A message containing logged data which requires a LOGGING_ACK to be sent back - public struct mavlink_logging_data_acked_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=109)] + /// Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED). + public struct mavlink_trajectory_representation_bezier_t { /// packet ordered constructor - public mavlink_logging_data_acked_t(ushort sequence,byte target_system,byte target_component,byte length,byte first_message_offset,byte[] data) + public mavlink_trajectory_representation_bezier_t(ulong time_usec,float[] pos_x,float[] pos_y,float[] pos_z,float[] delta,float[] pos_yaw,byte valid_points) { - this.sequence = sequence; - this.target_system = target_system; - this.target_component = target_component; - this.length = length; - this.first_message_offset = first_message_offset; - this.data = data; + this.time_usec = time_usec; + this.pos_x = pos_x; + this.pos_y = pos_y; + this.pos_z = pos_z; + this.delta = delta; + this.pos_yaw = pos_yaw; + this.valid_points = valid_points; } /// packet xml order - public static mavlink_logging_data_acked_t PopulateXMLOrder(byte target_system,byte target_component,ushort sequence,byte length,byte first_message_offset,byte[] data) + public static mavlink_trajectory_representation_bezier_t PopulateXMLOrder(ulong time_usec,byte valid_points,float[] pos_x,float[] pos_y,float[] pos_z,float[] delta,float[] pos_yaw) { - var msg = new mavlink_logging_data_acked_t(); + var msg = new mavlink_trajectory_representation_bezier_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.sequence = sequence; - msg.length = length; - msg.first_message_offset = first_message_offset; - msg.data = data; + msg.time_usec = time_usec; + msg.valid_points = valid_points; + msg.pos_x = pos_x; + msg.pos_y = pos_y; + msg.pos_z = pos_z; + msg.delta = delta; + msg.pos_yaw = pos_yaw; return msg; } - /// sequence number (can wrap) - [Units("")] - [Description("sequence number (can wrap)")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public ushort sequence; + public ulong time_usec; - /// system ID of the target - [Units("")] - [Description("system ID of the target")] - //[FieldOffset(2)] - public byte target_system; + /// X-coordinate of bezier control points. Set to NaN if not being used [m] + [Units("[m]")] + [Description("X-coordinate of bezier control points. Set to NaN if not being used")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_x; - /// component ID of the target - [Units("")] - [Description("component ID of the target")] - //[FieldOffset(3)] - public byte target_component; + /// Y-coordinate of bezier control points. Set to NaN if not being used [m] + [Units("[m]")] + [Description("Y-coordinate of bezier control points. Set to NaN if not being used")] + //[FieldOffset(28)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_y; - /// data length [bytes] - [Units("[bytes]")] - [Description("data length")] - //[FieldOffset(4)] - public byte length; + /// Z-coordinate of bezier control points. Set to NaN if not being used [m] + [Units("[m]")] + [Description("Z-coordinate of bezier control points. Set to NaN if not being used")] + //[FieldOffset(48)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_z; - /// offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). [bytes] - [Units("[bytes]")] - [Description("offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).")] - //[FieldOffset(5)] - public byte first_message_offset; + /// Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated [s] + [Units("[s]")] + [Description("Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated")] + //[FieldOffset(68)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] delta; - /// logged data + /// Yaw. Set to NaN for unchanged [rad] + [Units("[rad]")] + [Description("Yaw. Set to NaN for unchanged")] + //[FieldOffset(88)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public float[] pos_yaw; + + /// Number of valid control points (up-to 5 points are possible) [Units("")] - [Description("logged data")] - //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=249)] - public byte[] data; + [Description("Number of valid control points (up-to 5 points are possible)")] + //[FieldOffset(108)] + public byte valid_points; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - /// An ack for a LOGGING_DATA_ACKED message - public struct mavlink_logging_ack_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// Status of the Iridium SBD link. + public struct mavlink_isbd_link_status_t { /// packet ordered constructor - public mavlink_logging_ack_t(ushort sequence,byte target_system,byte target_component) + public mavlink_isbd_link_status_t(ulong timestamp,ulong last_heartbeat,ushort failed_sessions,ushort successful_sessions,byte signal_quality,byte ring_pending,byte tx_session_pending,byte rx_session_pending) { - this.sequence = sequence; - this.target_system = target_system; - this.target_component = target_component; + this.timestamp = timestamp; + this.last_heartbeat = last_heartbeat; + this.failed_sessions = failed_sessions; + this.successful_sessions = successful_sessions; + this.signal_quality = signal_quality; + this.ring_pending = ring_pending; + this.tx_session_pending = tx_session_pending; + this.rx_session_pending = rx_session_pending; } /// packet xml order - public static mavlink_logging_ack_t PopulateXMLOrder(byte target_system,byte target_component,ushort sequence) + public static mavlink_isbd_link_status_t PopulateXMLOrder(ulong timestamp,ulong last_heartbeat,ushort failed_sessions,ushort successful_sessions,byte signal_quality,byte ring_pending,byte tx_session_pending,byte rx_session_pending) { - var msg = new mavlink_logging_ack_t(); + var msg = new mavlink_isbd_link_status_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.sequence = sequence; + msg.timestamp = timestamp; + msg.last_heartbeat = last_heartbeat; + msg.failed_sessions = failed_sessions; + msg.successful_sessions = successful_sessions; + msg.signal_quality = signal_quality; + msg.ring_pending = ring_pending; + msg.tx_session_pending = tx_session_pending; + msg.rx_session_pending = rx_session_pending; return msg; } - /// sequence number (must match the one in LOGGING_DATA_ACKED) - [Units("")] - [Description("sequence number (must match the one in LOGGING_DATA_ACKED)")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public ushort sequence; + public ulong timestamp; - /// system ID of the target + /// Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. [us] + [Units("[us]")] + [Description("Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.")] + //[FieldOffset(8)] + public ulong last_heartbeat; + + /// Number of failed SBD sessions. [Units("")] - [Description("system ID of the target")] - //[FieldOffset(2)] - public byte target_system; + [Description("Number of failed SBD sessions.")] + //[FieldOffset(16)] + public ushort failed_sessions; - /// component ID of the target + /// Number of successful SBD sessions. [Units("")] - [Description("component ID of the target")] - //[FieldOffset(3)] - public byte target_component; + [Description("Number of successful SBD sessions.")] + //[FieldOffset(18)] + public ushort successful_sessions; + + /// Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. + [Units("")] + [Description("Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.")] + //[FieldOffset(20)] + public byte signal_quality; + + /// 1: Ring call pending, 0: No call pending. + [Units("")] + [Description("1: Ring call pending, 0: No call pending.")] + //[FieldOffset(21)] + public byte ring_pending; + + /// 1: Transmission session pending, 0: No transmission session pending. + [Units("")] + [Description("1: Transmission session pending, 0: No transmission session pending.")] + //[FieldOffset(22)] + public byte tx_session_pending; + + /// 1: Receiving session pending, 0: No receiving session pending. + [Units("")] + [Description("1: Receiving session pending, 0: No receiving session pending.")] + //[FieldOffset(23)] + public byte rx_session_pending; }; - - /// extensions_start 12 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=214)] - /// Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc. - public struct mavlink_video_stream_information_t + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// RPM sensor data message. + public struct mavlink_raw_rpm_t { /// packet ordered constructor - public mavlink_video_stream_information_t(float framerate,uint bitrate,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,ushort resolution_h,ushort resolution_v,ushort rotation,ushort hfov,byte stream_id,byte count,/*VIDEO_STREAM_TYPE*/byte type,byte[] name,byte[] uri,/*VIDEO_STREAM_ENCODING*/byte encoding) + public mavlink_raw_rpm_t(float frequency,byte index) { - this.framerate = framerate; - this.bitrate = bitrate; - this.flags = flags; - this.resolution_h = resolution_h; - this.resolution_v = resolution_v; - this.rotation = rotation; - this.hfov = hfov; - this.stream_id = stream_id; - this.count = count; - this.type = type; - this.name = name; - this.uri = uri; - this.encoding = encoding; + this.frequency = frequency; + this.index = index; } /// packet xml order - public static mavlink_video_stream_information_t PopulateXMLOrder(byte stream_id,byte count,/*VIDEO_STREAM_TYPE*/byte type,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,ushort hfov,byte[] name,byte[] uri,/*VIDEO_STREAM_ENCODING*/byte encoding) + public static mavlink_raw_rpm_t PopulateXMLOrder(byte index,float frequency) { - var msg = new mavlink_video_stream_information_t(); + var msg = new mavlink_raw_rpm_t(); - msg.stream_id = stream_id; - msg.count = count; - msg.type = type; - msg.flags = flags; - msg.framerate = framerate; - msg.resolution_h = resolution_h; - msg.resolution_v = resolution_v; - msg.bitrate = bitrate; - msg.rotation = rotation; - msg.hfov = hfov; - msg.name = name; - msg.uri = uri; - msg.encoding = encoding; + msg.index = index; + msg.frequency = frequency; return msg; } - /// Frame rate. [Hz] - [Units("[Hz]")] - [Description("Frame rate.")] + /// Indicated rate [rpm] + [Units("[rpm]")] + [Description("Indicated rate")] //[FieldOffset(0)] - public float framerate; - - /// Bit rate. [bits/s] - [Units("[bits/s]")] - [Description("Bit rate.")] - //[FieldOffset(4)] - public uint bitrate; - - /// Bitmap of stream status flags. VIDEO_STREAM_STATUS_FLAGS - [Units("")] - [Description("Bitmap of stream status flags.")] - //[FieldOffset(8)] - public /*VIDEO_STREAM_STATUS_FLAGS*/ushort flags; - - /// Horizontal resolution. [pix] - [Units("[pix]")] - [Description("Horizontal resolution.")] - //[FieldOffset(10)] - public ushort resolution_h; - - /// Vertical resolution. [pix] - [Units("[pix]")] - [Description("Vertical resolution.")] - //[FieldOffset(12)] - public ushort resolution_v; - - /// Video image rotation clockwise. [deg] - [Units("[deg]")] - [Description("Video image rotation clockwise.")] - //[FieldOffset(14)] - public ushort rotation; - - /// Horizontal Field of view. [deg] - [Units("[deg]")] - [Description("Horizontal Field of view.")] - //[FieldOffset(16)] - public ushort hfov; - - /// Video Stream ID (1 for first, 2 for second, etc.) - [Units("")] - [Description("Video Stream ID (1 for first, 2 for second, etc.)")] - //[FieldOffset(18)] - public byte stream_id; - - /// Number of streams available. - [Units("")] - [Description("Number of streams available.")] - //[FieldOffset(19)] - public byte count; - - /// Type of stream. VIDEO_STREAM_TYPE - [Units("")] - [Description("Type of stream.")] - //[FieldOffset(20)] - public /*VIDEO_STREAM_TYPE*/byte type; - - /// Stream name. - [Units("")] - [Description("Stream name.")] - //[FieldOffset(21)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] name; - - /// Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - [Units("")] - [Description("Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).")] - //[FieldOffset(53)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=160)] - public byte[] uri; + public float frequency; - /// Encoding of stream. VIDEO_STREAM_ENCODING + /// Index of this RPM sensor (0-indexed) [Units("")] - [Description("Encoding of stream.")] - //[FieldOffset(213)] - public /*VIDEO_STREAM_ENCODING*/byte encoding; + [Description("Index of this RPM sensor (0-indexed)")] + //[FieldOffset(4)] + public byte index; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] - /// Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE. - public struct mavlink_video_stream_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=70)] + /// The global position resulting from GPS and sensor fusion. + public struct mavlink_utm_global_position_t { /// packet ordered constructor - public mavlink_video_stream_status_t(float framerate,uint bitrate,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,ushort resolution_h,ushort resolution_v,ushort rotation,ushort hfov,byte stream_id) + public mavlink_utm_global_position_t(ulong time,int lat,int lon,int alt,int relative_alt,int next_lat,int next_lon,int next_alt,short vx,short vy,short vz,ushort h_acc,ushort v_acc,ushort vel_acc,ushort update_rate,byte[] uas_id,/*UTM_FLIGHT_STATE*/byte flight_state,/*UTM_DATA_AVAIL_FLAGS*/byte flags) { - this.framerate = framerate; - this.bitrate = bitrate; + this.time = time; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.relative_alt = relative_alt; + this.next_lat = next_lat; + this.next_lon = next_lon; + this.next_alt = next_alt; + this.vx = vx; + this.vy = vy; + this.vz = vz; + this.h_acc = h_acc; + this.v_acc = v_acc; + this.vel_acc = vel_acc; + this.update_rate = update_rate; + this.uas_id = uas_id; + this.flight_state = flight_state; this.flags = flags; - this.resolution_h = resolution_h; - this.resolution_v = resolution_v; - this.rotation = rotation; - this.hfov = hfov; - this.stream_id = stream_id; } /// packet xml order - public static mavlink_video_stream_status_t PopulateXMLOrder(byte stream_id,/*VIDEO_STREAM_STATUS_FLAGS*/ushort flags,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,ushort hfov) + public static mavlink_utm_global_position_t PopulateXMLOrder(ulong time,byte[] uas_id,int lat,int lon,int alt,int relative_alt,short vx,short vy,short vz,ushort h_acc,ushort v_acc,ushort vel_acc,int next_lat,int next_lon,int next_alt,ushort update_rate,/*UTM_FLIGHT_STATE*/byte flight_state,/*UTM_DATA_AVAIL_FLAGS*/byte flags) { - var msg = new mavlink_video_stream_status_t(); + var msg = new mavlink_utm_global_position_t(); - msg.stream_id = stream_id; + msg.time = time; + msg.uas_id = uas_id; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.relative_alt = relative_alt; + msg.vx = vx; + msg.vy = vy; + msg.vz = vz; + msg.h_acc = h_acc; + msg.v_acc = v_acc; + msg.vel_acc = vel_acc; + msg.next_lat = next_lat; + msg.next_lon = next_lon; + msg.next_alt = next_alt; + msg.update_rate = update_rate; + msg.flight_state = flight_state; msg.flags = flags; - msg.framerate = framerate; - msg.resolution_h = resolution_h; - msg.resolution_v = resolution_v; - msg.bitrate = bitrate; - msg.rotation = rotation; - msg.hfov = hfov; return msg; } - /// Frame rate [Hz] - [Units("[Hz]")] - [Description("Frame rate")] + /// Time of applicability of position (microseconds since UNIX epoch). [us] + [Units("[us]")] + [Description("Time of applicability of position (microseconds since UNIX epoch).")] //[FieldOffset(0)] - public float framerate; - - /// Bit rate [bits/s] - [Units("[bits/s]")] - [Description("Bit rate")] - //[FieldOffset(4)] - public uint bitrate; + public ulong time; - /// Bitmap of stream status flags VIDEO_STREAM_STATUS_FLAGS - [Units("")] - [Description("Bitmap of stream status flags")] + /// Latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Latitude (WGS84)")] //[FieldOffset(8)] - public /*VIDEO_STREAM_STATUS_FLAGS*/ushort flags; - - /// Horizontal resolution [pix] - [Units("[pix]")] - [Description("Horizontal resolution")] - //[FieldOffset(10)] - public ushort resolution_h; + public int lat; - /// Vertical resolution [pix] - [Units("[pix]")] - [Description("Vertical resolution")] + /// Longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Longitude (WGS84)")] //[FieldOffset(12)] - public ushort resolution_v; - - /// Video image rotation clockwise [deg] - [Units("[deg]")] - [Description("Video image rotation clockwise")] - //[FieldOffset(14)] - public ushort rotation; + public int lon; - /// Horizontal Field of view [deg] - [Units("[deg]")] - [Description("Horizontal Field of view")] + /// Altitude (WGS84) [mm] + [Units("[mm]")] + [Description("Altitude (WGS84)")] //[FieldOffset(16)] - public ushort hfov; + public int alt; - /// Video Stream ID (1 for first, 2 for second, etc.) + /// Altitude above ground [mm] + [Units("[mm]")] + [Description("Altitude above ground")] + //[FieldOffset(20)] + public int relative_alt; + + /// Next waypoint, latitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Next waypoint, latitude (WGS84)")] + //[FieldOffset(24)] + public int next_lat; + + /// Next waypoint, longitude (WGS84) [degE7] + [Units("[degE7]")] + [Description("Next waypoint, longitude (WGS84)")] + //[FieldOffset(28)] + public int next_lon; + + /// Next waypoint, altitude (WGS84) [mm] + [Units("[mm]")] + [Description("Next waypoint, altitude (WGS84)")] + //[FieldOffset(32)] + public int next_alt; + + /// Ground X speed (latitude, positive north) [cm/s] + [Units("[cm/s]")] + [Description("Ground X speed (latitude, positive north)")] + //[FieldOffset(36)] + public short vx; + + /// Ground Y speed (longitude, positive east) [cm/s] + [Units("[cm/s]")] + [Description("Ground Y speed (longitude, positive east)")] + //[FieldOffset(38)] + public short vy; + + /// Ground Z speed (altitude, positive down) [cm/s] + [Units("[cm/s]")] + [Description("Ground Z speed (altitude, positive down)")] + //[FieldOffset(40)] + public short vz; + + /// Horizontal position uncertainty (standard deviation) [mm] + [Units("[mm]")] + [Description("Horizontal position uncertainty (standard deviation)")] + //[FieldOffset(42)] + public ushort h_acc; + + /// Altitude uncertainty (standard deviation) [mm] + [Units("[mm]")] + [Description("Altitude uncertainty (standard deviation)")] + //[FieldOffset(44)] + public ushort v_acc; + + /// Speed uncertainty (standard deviation) [cm/s] + [Units("[cm/s]")] + [Description("Speed uncertainty (standard deviation)")] + //[FieldOffset(46)] + public ushort vel_acc; + + /// Time until next update. Set to 0 if unknown or in data driven mode. [cs] + [Units("[cs]")] + [Description("Time until next update. Set to 0 if unknown or in data driven mode.")] + //[FieldOffset(48)] + public ushort update_rate; + + /// Unique UAS ID. [Units("")] - [Description("Video Stream ID (1 for first, 2 for second, etc.)")] - //[FieldOffset(18)] - public byte stream_id; + [Description("Unique UAS ID.")] + //[FieldOffset(50)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=18)] + public byte[] uas_id; + + /// Flight state UTM_FLIGHT_STATE + [Units("")] + [Description("Flight state")] + //[FieldOffset(68)] + public /*UTM_FLIGHT_STATE*/byte flight_state; + + /// Bitwise OR combination of the data available flags. UTM_DATA_AVAIL_FLAGS bitmask + [Units("")] + [Description("Bitwise OR combination of the data available flags.")] + //[FieldOffset(69)] + public /*UTM_DATA_AVAIL_FLAGS*/byte flags; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] - /// Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - public struct mavlink_camera_fov_status_t + /// extensions_start 3 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=252)] + /// Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code. + public struct mavlink_debug_float_array_t { /// packet ordered constructor - public mavlink_camera_fov_status_t(uint time_boot_ms,int lat_camera,int lon_camera,int alt_camera,int lat_image,int lon_image,int alt_image,float[] q,float hfov,float vfov) - { - this.time_boot_ms = time_boot_ms; - this.lat_camera = lat_camera; - this.lon_camera = lon_camera; - this.alt_camera = alt_camera; - this.lat_image = lat_image; - this.lon_image = lon_image; - this.alt_image = alt_image; - this.q = q; - this.hfov = hfov; - this.vfov = vfov; + public mavlink_debug_float_array_t(ulong time_usec,ushort array_id,byte[] name,float[] data) + { + this.time_usec = time_usec; + this.array_id = array_id; + this.name = name; + this.data = data; } /// packet xml order - public static mavlink_camera_fov_status_t PopulateXMLOrder(uint time_boot_ms,int lat_camera,int lon_camera,int alt_camera,int lat_image,int lon_image,int alt_image,float[] q,float hfov,float vfov) + public static mavlink_debug_float_array_t PopulateXMLOrder(ulong time_usec,byte[] name,ushort array_id,float[] data) { - var msg = new mavlink_camera_fov_status_t(); + var msg = new mavlink_debug_float_array_t(); - msg.time_boot_ms = time_boot_ms; - msg.lat_camera = lat_camera; - msg.lon_camera = lon_camera; - msg.alt_camera = alt_camera; - msg.lat_image = lat_image; - msg.lon_image = lon_image; - msg.alt_image = alt_image; - msg.q = q; - msg.hfov = hfov; - msg.vfov = vfov; + msg.time_usec = time_usec; + msg.name = name; + msg.array_id = array_id; + msg.data = data; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// 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. [us] + [Units("[us]")] + [Description("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.")] //[FieldOffset(0)] - public uint time_boot_ms; - - /// Latitude of camera (INT32_MAX if unknown). [degE7] - [Units("[degE7]")] - [Description("Latitude of camera (INT32_MAX if unknown).")] - //[FieldOffset(4)] - public int lat_camera; + public ulong time_usec; - /// Longitude of camera (INT32_MAX if unknown). [degE7] - [Units("[degE7]")] - [Description("Longitude of camera (INT32_MAX if unknown).")] + /// Unique ID used to discriminate between arrays + [Units("")] + [Description("Unique ID used to discriminate between arrays")] //[FieldOffset(8)] - public int lon_camera; - - /// Altitude (MSL) of camera (INT32_MAX if unknown). [mm] - [Units("[mm]")] - [Description("Altitude (MSL) of camera (INT32_MAX if unknown).")] - //[FieldOffset(12)] - public int alt_camera; - - /// Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). [degE7] - [Units("[degE7]")] - [Description("Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).")] - //[FieldOffset(16)] - public int lat_image; - - /// Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). [degE7] - [Units("[degE7]")] - [Description("Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).")] - //[FieldOffset(20)] - public int lon_image; - - /// Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). [mm] - [Units("[mm]")] - [Description("Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).")] - //[FieldOffset(24)] - public int alt_image; + public ushort array_id; - /// Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + /// Name, for human-friendly display in a Ground Control Station [Units("")] - [Description("Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)")] - //[FieldOffset(28)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// Horizontal field of view (NaN if unknown). [deg] - [Units("[deg]")] - [Description("Horizontal field of view (NaN if unknown).")] - //[FieldOffset(44)] - public float hfov; + [Description("Name, for human-friendly display in a Ground Control Station")] + //[FieldOffset(10)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public byte[] name; - /// Vertical field of view (NaN if unknown). [deg] - [Units("[deg]")] - [Description("Vertical field of view (NaN if unknown).")] - //[FieldOffset(48)] - public float vfov; + /// data + [Units("")] + [Description("data")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=58)] + public float[] data; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)] - /// Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval. - public struct mavlink_camera_tracking_image_status_t + /// extensions_start 12 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=109)] + /// Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for smart battery frequent updates. + public struct mavlink_smart_battery_info_t { /// packet ordered constructor - public mavlink_camera_tracking_image_status_t(float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y,/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status,/*CAMERA_TRACKING_MODE*/byte tracking_mode,/*CAMERA_TRACKING_TARGET_DATA*/byte target_data) + public mavlink_smart_battery_info_t(int capacity_full_specification,int capacity_full,ushort cycle_count,ushort weight,ushort discharge_minimum_voltage,ushort charging_minimum_voltage,ushort resting_minimum_voltage,byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,byte[] serial_number,byte[] device_name,ushort charging_maximum_voltage,byte cells_in_series,uint discharge_maximum_current,uint discharge_maximum_burst_current,byte[] manufacture_date) { - this.point_x = point_x; - this.point_y = point_y; - this.radius = radius; - this.rec_top_x = rec_top_x; - this.rec_top_y = rec_top_y; - this.rec_bottom_x = rec_bottom_x; - this.rec_bottom_y = rec_bottom_y; - this.tracking_status = tracking_status; - this.tracking_mode = tracking_mode; - this.target_data = target_data; + this.capacity_full_specification = capacity_full_specification; + this.capacity_full = capacity_full; + this.cycle_count = cycle_count; + this.weight = weight; + this.discharge_minimum_voltage = discharge_minimum_voltage; + this.charging_minimum_voltage = charging_minimum_voltage; + this.resting_minimum_voltage = resting_minimum_voltage; + this.id = id; + this.battery_function = battery_function; + this.type = type; + this.serial_number = serial_number; + this.device_name = device_name; + this.charging_maximum_voltage = charging_maximum_voltage; + this.cells_in_series = cells_in_series; + this.discharge_maximum_current = discharge_maximum_current; + this.discharge_maximum_burst_current = discharge_maximum_burst_current; + this.manufacture_date = manufacture_date; } /// packet xml order - public static mavlink_camera_tracking_image_status_t PopulateXMLOrder(/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status,/*CAMERA_TRACKING_MODE*/byte tracking_mode,/*CAMERA_TRACKING_TARGET_DATA*/byte target_data,float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y) + public static mavlink_smart_battery_info_t PopulateXMLOrder(byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,int capacity_full_specification,int capacity_full,ushort cycle_count,byte[] serial_number,byte[] device_name,ushort weight,ushort discharge_minimum_voltage,ushort charging_minimum_voltage,ushort resting_minimum_voltage,ushort charging_maximum_voltage,byte cells_in_series,uint discharge_maximum_current,uint discharge_maximum_burst_current,byte[] manufacture_date) { - var msg = new mavlink_camera_tracking_image_status_t(); + var msg = new mavlink_smart_battery_info_t(); - msg.tracking_status = tracking_status; - msg.tracking_mode = tracking_mode; - msg.target_data = target_data; - msg.point_x = point_x; - msg.point_y = point_y; - msg.radius = radius; - msg.rec_top_x = rec_top_x; - msg.rec_top_y = rec_top_y; - msg.rec_bottom_x = rec_bottom_x; - msg.rec_bottom_y = rec_bottom_y; + msg.id = id; + msg.battery_function = battery_function; + msg.type = type; + msg.capacity_full_specification = capacity_full_specification; + msg.capacity_full = capacity_full; + msg.cycle_count = cycle_count; + msg.serial_number = serial_number; + msg.device_name = device_name; + msg.weight = weight; + msg.discharge_minimum_voltage = discharge_minimum_voltage; + msg.charging_minimum_voltage = charging_minimum_voltage; + msg.resting_minimum_voltage = resting_minimum_voltage; + msg.charging_maximum_voltage = charging_maximum_voltage; + msg.cells_in_series = cells_in_series; + msg.discharge_maximum_current = discharge_maximum_current; + msg.discharge_maximum_burst_current = discharge_maximum_burst_current; + msg.manufacture_date = manufacture_date; return msg; } - /// Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown - [Units("")] - [Description("Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown")] + /// Capacity when full according to manufacturer, -1: field not provided. [mAh] + [Units("[mAh]")] + [Description("Capacity when full according to manufacturer, -1: field not provided.")] //[FieldOffset(0)] - public float point_x; + public int capacity_full_specification; - /// Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - [Units("")] - [Description("Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown")] + /// Capacity when full (accounting for battery degradation), -1: field not provided. [mAh] + [Units("[mAh]")] + [Description("Capacity when full (accounting for battery degradation), -1: field not provided.")] //[FieldOffset(4)] - public float point_y; + public int capacity_full; - /// Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown + /// Charge/discharge cycle count. UINT16_MAX: field not provided. [Units("")] - [Description("Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown")] + [Description("Charge/discharge cycle count. UINT16_MAX: field not provided.")] //[FieldOffset(8)] - public float radius; + public ushort cycle_count; - /// Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - [Units("")] - [Description("Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown")] + /// Battery weight. 0: field not provided. [g] + [Units("[g]")] + [Description("Battery weight. 0: field not provided.")] + //[FieldOffset(10)] + public ushort weight; + + /// Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. [mV] + [Units("[mV]")] + [Description("Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value.")] //[FieldOffset(12)] - public float rec_top_x; + public ushort discharge_minimum_voltage; - /// Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - [Units("")] - [Description("Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown")] + /// Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. [mV] + [Units("[mV]")] + [Description("Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value.")] + //[FieldOffset(14)] + public ushort charging_minimum_voltage; + + /// Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. [mV] + [Units("[mV]")] + [Description("Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value.")] //[FieldOffset(16)] - public float rec_top_y; + public ushort resting_minimum_voltage; - /// Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown + /// Battery ID [Units("")] - [Description("Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown")] + [Description("Battery ID")] + //[FieldOffset(18)] + public byte id; + + /// Function of the battery MAV_BATTERY_FUNCTION + [Units("")] + [Description("Function of the battery")] + //[FieldOffset(19)] + public /*MAV_BATTERY_FUNCTION*/byte battery_function; + + /// Type (chemistry) of the battery MAV_BATTERY_TYPE + [Units("")] + [Description("Type (chemistry) of the battery")] //[FieldOffset(20)] - public float rec_bottom_x; + public /*MAV_BATTERY_TYPE*/byte type; - /// Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown + /// Serial number in ASCII characters, 0 terminated. All 0: field not provided. [Units("")] - [Description("Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown")] - //[FieldOffset(24)] - public float rec_bottom_y; + [Description("Serial number in ASCII characters, 0 terminated. All 0: field not provided.")] + //[FieldOffset(21)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public byte[] serial_number; - /// Current tracking status CAMERA_TRACKING_STATUS_FLAGS + /// Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. [Units("")] - [Description("Current tracking status")] - //[FieldOffset(28)] - public /*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status; + [Description("Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore.")] + //[FieldOffset(37)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] device_name; - /// Current tracking mode CAMERA_TRACKING_MODE + /// Maximum per-cell voltage when charged. 0: field not provided. [mV] + [Units("[mV]")] + [Description("Maximum per-cell voltage when charged. 0: field not provided.")] + //[FieldOffset(87)] + public ushort charging_maximum_voltage; + + /// Number of battery cells in series. 0: field not provided. [Units("")] - [Description("Current tracking mode")] - //[FieldOffset(29)] - public /*CAMERA_TRACKING_MODE*/byte tracking_mode; + [Description("Number of battery cells in series. 0: field not provided.")] + //[FieldOffset(89)] + public byte cells_in_series; - /// Defines location of target data CAMERA_TRACKING_TARGET_DATA + /// Maximum pack discharge current. 0: field not provided. [mA] + [Units("[mA]")] + [Description("Maximum pack discharge current. 0: field not provided.")] + //[FieldOffset(90)] + public uint discharge_maximum_current; + + /// Maximum pack discharge burst current. 0: field not provided. [mA] + [Units("[mA]")] + [Description("Maximum pack discharge burst current. 0: field not provided.")] + //[FieldOffset(94)] + public uint discharge_maximum_burst_current; + + /// Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. [Units("")] - [Description("Defines location of target data")] - //[FieldOffset(30)] - public /*CAMERA_TRACKING_TARGET_DATA*/byte target_data; + [Description("Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided.")] + //[FieldOffset(98)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=11)] + public byte[] manufacture_date; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=49)] - /// Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval. - public struct mavlink_camera_tracking_geo_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Telemetry of power generation system. Alternator or mechanical generator. + public struct mavlink_generator_status_t { /// packet ordered constructor - public mavlink_camera_tracking_geo_status_t(int lat,int lon,float alt,float h_acc,float v_acc,float vel_n,float vel_e,float vel_d,float vel_acc,float dist,float hdg,float hdg_acc,/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status) + public mavlink_generator_status_t(/*MAV_GENERATOR_STATUS_FLAG*/ulong status,float battery_current,float load_current,float power_generated,float bus_voltage,float bat_current_setpoint,uint runtime,int time_until_maintenance,ushort generator_speed,short rectifier_temperature,short generator_temperature) { - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.h_acc = h_acc; - this.v_acc = v_acc; - this.vel_n = vel_n; - this.vel_e = vel_e; - this.vel_d = vel_d; - this.vel_acc = vel_acc; - this.dist = dist; - this.hdg = hdg; - this.hdg_acc = hdg_acc; - this.tracking_status = tracking_status; + this.status = status; + this.battery_current = battery_current; + this.load_current = load_current; + this.power_generated = power_generated; + this.bus_voltage = bus_voltage; + this.bat_current_setpoint = bat_current_setpoint; + this.runtime = runtime; + this.time_until_maintenance = time_until_maintenance; + this.generator_speed = generator_speed; + this.rectifier_temperature = rectifier_temperature; + this.generator_temperature = generator_temperature; } /// packet xml order - public static mavlink_camera_tracking_geo_status_t PopulateXMLOrder(/*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status,int lat,int lon,float alt,float h_acc,float v_acc,float vel_n,float vel_e,float vel_d,float vel_acc,float dist,float hdg,float hdg_acc) + public static mavlink_generator_status_t PopulateXMLOrder(/*MAV_GENERATOR_STATUS_FLAG*/ulong status,ushort generator_speed,float battery_current,float load_current,float power_generated,float bus_voltage,short rectifier_temperature,float bat_current_setpoint,short generator_temperature,uint runtime,int time_until_maintenance) { - var msg = new mavlink_camera_tracking_geo_status_t(); + var msg = new mavlink_generator_status_t(); - msg.tracking_status = tracking_status; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.h_acc = h_acc; - msg.v_acc = v_acc; - msg.vel_n = vel_n; - msg.vel_e = vel_e; - msg.vel_d = vel_d; - msg.vel_acc = vel_acc; - msg.dist = dist; - msg.hdg = hdg; - msg.hdg_acc = hdg_acc; + msg.status = status; + msg.generator_speed = generator_speed; + msg.battery_current = battery_current; + msg.load_current = load_current; + msg.power_generated = power_generated; + msg.bus_voltage = bus_voltage; + msg.rectifier_temperature = rectifier_temperature; + msg.bat_current_setpoint = bat_current_setpoint; + msg.generator_temperature = generator_temperature; + msg.runtime = runtime; + msg.time_until_maintenance = time_until_maintenance; return msg; } - /// Latitude of tracked object [degE7] - [Units("[degE7]")] - [Description("Latitude of tracked object")] + /// Status flags. MAV_GENERATOR_STATUS_FLAG bitmask + [Units("")] + [Description("Status flags.")] //[FieldOffset(0)] - public int lat; - - /// Longitude of tracked object [degE7] - [Units("[degE7]")] - [Description("Longitude of tracked object")] - //[FieldOffset(4)] - public int lon; + public /*MAV_GENERATOR_STATUS_FLAG*/ulong status; - /// Altitude of tracked object(AMSL, WGS84) [m] - [Units("[m]")] - [Description("Altitude of tracked object(AMSL, WGS84)")] + /// Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. [A] + [Units("[A]")] + [Description("Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.")] //[FieldOffset(8)] - public float alt; + public float battery_current; - /// Horizontal accuracy. NAN if unknown [m] - [Units("[m]")] - [Description("Horizontal accuracy. NAN if unknown")] + /// Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided [A] + [Units("[A]")] + [Description("Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided")] //[FieldOffset(12)] - public float h_acc; + public float load_current; - /// Vertical accuracy. NAN if unknown [m] - [Units("[m]")] - [Description("Vertical accuracy. NAN if unknown")] + /// The power being generated. NaN: field not provided [W] + [Units("[W]")] + [Description("The power being generated. NaN: field not provided")] //[FieldOffset(16)] - public float v_acc; + public float power_generated; - /// North velocity of tracked object. NAN if unknown [m/s] - [Units("[m/s]")] - [Description("North velocity of tracked object. NAN if unknown")] + /// Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. [V] + [Units("[V]")] + [Description("Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.")] //[FieldOffset(20)] - public float vel_n; + public float bus_voltage; - /// East velocity of tracked object. NAN if unknown [m/s] - [Units("[m/s]")] - [Description("East velocity of tracked object. NAN if unknown")] + /// The target battery current. Positive for out. Negative for in. NaN: field not provided [A] + [Units("[A]")] + [Description("The target battery current. Positive for out. Negative for in. NaN: field not provided")] //[FieldOffset(24)] - public float vel_e; + public float bat_current_setpoint; - /// Down velocity of tracked object. NAN if unknown [m/s] - [Units("[m/s]")] - [Description("Down velocity of tracked object. NAN if unknown")] + /// Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. [s] + [Units("[s]")] + [Description("Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.")] //[FieldOffset(28)] - public float vel_d; + public uint runtime; - /// Velocity accuracy. NAN if unknown [m/s] - [Units("[m/s]")] - [Description("Velocity accuracy. NAN if unknown")] + /// Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. [s] + [Units("[s]")] + [Description("Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.")] //[FieldOffset(32)] - public float vel_acc; + public int time_until_maintenance; - /// Distance between camera and tracked object. NAN if unknown [m] - [Units("[m]")] - [Description("Distance between camera and tracked object. NAN if unknown")] + /// Speed of electrical generator or alternator. UINT16_MAX: field not provided. [rpm] + [Units("[rpm]")] + [Description("Speed of electrical generator or alternator. UINT16_MAX: field not provided.")] //[FieldOffset(36)] - public float dist; + public ushort generator_speed; - /// Heading in radians, in NED. NAN if unknown [rad] - [Units("[rad]")] - [Description("Heading in radians, in NED. NAN if unknown")] + /// The temperature of the rectifier or power converter. INT16_MAX: field not provided. [degC] + [Units("[degC]")] + [Description("The temperature of the rectifier or power converter. INT16_MAX: field not provided.")] + //[FieldOffset(38)] + public short rectifier_temperature; + + /// The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. [degC] + [Units("[degC]")] + [Description("The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.")] //[FieldOffset(40)] - public float hdg; + public short generator_temperature; + }; - /// Accuracy of heading, in NED. NAN if unknown [rad] - [Units("[rad]")] - [Description("Accuracy of heading, in NED. NAN if unknown")] - //[FieldOffset(44)] - public float hdg_acc; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=140)] + /// The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW. + public struct mavlink_actuator_output_status_t + { + /// packet ordered constructor + public mavlink_actuator_output_status_t(ulong time_usec,uint active,float[] actuator) + { + this.time_usec = time_usec; + this.active = active; + this.actuator = actuator; + + } + + /// packet xml order + public static mavlink_actuator_output_status_t PopulateXMLOrder(ulong time_usec,uint active,float[] actuator) + { + var msg = new mavlink_actuator_output_status_t(); - /// Current tracking status CAMERA_TRACKING_STATUS_FLAGS + msg.time_usec = time_usec; + msg.active = active; + msg.actuator = actuator; + + return msg; + } + + + /// Timestamp (since system boot). [us] + [Units("[us]")] + [Description("Timestamp (since system boot).")] + //[FieldOffset(0)] + public ulong time_usec; + + /// Active outputs bitmask [Units("")] - [Description("Current tracking status")] - //[FieldOffset(48)] - public /*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status; + [Description("Active outputs")] + //[FieldOffset(8)] + public uint active; + + /// Servo / motor output array values. Zero values indicate unused channels. + [Units("")] + [Description("Servo / motor output array values. Zero values indicate unused channels.")] + //[FieldOffset(12)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public float[] actuator; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] - /// Camera absolute thermal range. This can be streamed when the associated `VIDEO_STREAM_STATUS.flag` bit `VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED` is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras). - public struct mavlink_camera_thermal_range_t + [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_camera_thermal_range_t(uint time_boot_ms,float max,float max_point_x,float max_point_y,float min,float min_point_x,float min_point_y,byte stream_id,byte camera_device_id) - { - this.time_boot_ms = time_boot_ms; - this.max = max; - this.max_point_x = max_point_x; - this.max_point_y = max_point_y; - this.min = min; - this.min_point_x = min_point_x; - this.min_point_y = min_point_y; - this.stream_id = stream_id; - this.camera_device_id = camera_device_id; + 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_camera_thermal_range_t PopulateXMLOrder(uint time_boot_ms,byte stream_id,byte camera_device_id,float max,float max_point_x,float max_point_y,float min,float min_point_x,float min_point_y) + public static mavlink_relay_status_t PopulateXMLOrder(uint time_boot_ms,ushort on,ushort present) { - var msg = new mavlink_camera_thermal_range_t(); + var msg = new mavlink_relay_status_t(); msg.time_boot_ms = time_boot_ms; - msg.stream_id = stream_id; - msg.camera_device_id = camera_device_id; - msg.max = max; - msg.max_point_x = max_point_x; - msg.max_point_y = max_point_y; - msg.min = min; - msg.min_point_x = min_point_x; - msg.min_point_y = min_point_y; + msg.on = on; + msg.present = present; return msg; } @@ -26675,4772 +32260,4696 @@ public static mavlink_camera_thermal_range_t PopulateXMLOrder(uint time_boot_ms, //[FieldOffset(0)] public uint time_boot_ms; - /// Temperature max. [degC] - [Units("[degC]")] - [Description("Temperature max.")] - //[FieldOffset(4)] - public float max; - - /// Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown. - [Units("")] - [Description("Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.")] - //[FieldOffset(8)] - public float max_point_x; - - /// Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown. - [Units("")] - [Description("Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.")] - //[FieldOffset(12)] - public float max_point_y; - - /// Temperature min. [degC] - [Units("[degC]")] - [Description("Temperature min.")] - //[FieldOffset(16)] - public float min; - - /// Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown. - [Units("")] - [Description("Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown.")] - //[FieldOffset(20)] - public float min_point_x; - - /// Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown. - [Units("")] - [Description("Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown.")] - //[FieldOffset(24)] - public float min_point_y; - - /// Video Stream ID (1 for first, 2 for second, etc.) + /// Relay states. Relay instance numbers are represented as individual bits in this mask by offset. bitmask [Units("")] - [Description("Video Stream ID (1 for first, 2 for second, etc.)")] - //[FieldOffset(28)] - public byte stream_id; + [Description("Relay states. Relay instance numbers are represented as individual bits in this mask by offset.")] + //[FieldOffset(4)] + public ushort on; - /// Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + /// 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("Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id).")] - //[FieldOffset(29)] - public byte camera_device_id; + [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=33)] - /// Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. - public struct mavlink_gimbal_manager_information_t + [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. + public struct mavlink_tunnel_t { /// packet ordered constructor - public mavlink_gimbal_manager_information_t(uint time_boot_ms,/*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,byte gimbal_device_id) + public mavlink_tunnel_t(/*MAV_TUNNEL_PAYLOAD_TYPE*/ushort payload_type,byte target_system,byte target_component,byte payload_length,byte[] payload) { - this.time_boot_ms = time_boot_ms; - this.cap_flags = cap_flags; - this.roll_min = roll_min; - this.roll_max = roll_max; - this.pitch_min = pitch_min; - this.pitch_max = pitch_max; - this.yaw_min = yaw_min; - this.yaw_max = yaw_max; - this.gimbal_device_id = gimbal_device_id; + this.payload_type = payload_type; + this.target_system = target_system; + this.target_component = target_component; + this.payload_length = payload_length; + this.payload = payload; } /// packet xml order - public static mavlink_gimbal_manager_information_t PopulateXMLOrder(uint time_boot_ms,/*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags,byte gimbal_device_id,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) + public static mavlink_tunnel_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_TUNNEL_PAYLOAD_TYPE*/ushort payload_type,byte payload_length,byte[] payload) { - var msg = new mavlink_gimbal_manager_information_t(); + var msg = new mavlink_tunnel_t(); - msg.time_boot_ms = time_boot_ms; - msg.cap_flags = cap_flags; - msg.gimbal_device_id = gimbal_device_id; - msg.roll_min = roll_min; - msg.roll_max = roll_max; - msg.pitch_min = pitch_min; - msg.pitch_max = pitch_max; - msg.yaw_min = yaw_min; - msg.yaw_max = yaw_max; + msg.target_system = target_system; + msg.target_component = target_component; + msg.payload_type = payload_type; + msg.payload_length = payload_length; + msg.payload = payload; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. MAV_TUNNEL_PAYLOAD_TYPE + [Units("")] + [Description("A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.")] //[FieldOffset(0)] - public uint time_boot_ms; + public /*MAV_TUNNEL_PAYLOAD_TYPE*/ushort payload_type; - /// Bitmap of gimbal capability flags. GIMBAL_MANAGER_CAP_FLAGS bitmask + /// System ID (can be 0 for broadcast, but this is discouraged) [Units("")] - [Description("Bitmap of gimbal capability flags.")] - //[FieldOffset(4)] - public /*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags; - - /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] - [Units("[rad]")] - [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] - //[FieldOffset(8)] - public float roll_min; - - /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] - [Units("[rad]")] - [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] - //[FieldOffset(12)] - public float roll_max; - - /// Minimum pitch angle (positive: up, negative: down) [rad] - [Units("[rad]")] - [Description("Minimum pitch angle (positive: up, negative: down)")] - //[FieldOffset(16)] - public float pitch_min; - - /// Maximum pitch angle (positive: up, negative: down) [rad] - [Units("[rad]")] - [Description("Maximum pitch angle (positive: up, negative: down)")] - //[FieldOffset(20)] - public float pitch_max; + [Description("System ID (can be 0 for broadcast, but this is discouraged)")] + //[FieldOffset(2)] + public byte target_system; - /// Minimum yaw angle (positive: to the right, negative: to the left) [rad] - [Units("[rad]")] - [Description("Minimum yaw angle (positive: to the right, negative: to the left)")] - //[FieldOffset(24)] - public float yaw_min; + /// Component ID (can be 0 for broadcast, but this is discouraged) + [Units("")] + [Description("Component ID (can be 0 for broadcast, but this is discouraged)")] + //[FieldOffset(3)] + public byte target_component; - /// Maximum yaw angle (positive: to the right, negative: to the left) [rad] - [Units("[rad]")] - [Description("Maximum yaw angle (positive: to the right, negative: to the left)")] - //[FieldOffset(28)] - public float yaw_max; + /// Length of the data transported in payload + [Units("")] + [Description("Length of the data transported in payload")] + //[FieldOffset(4)] + public byte payload_length; - /// Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). + /// Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. [Units("")] - [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; + [Description("Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type.")] + //[FieldOffset(5)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] + public byte[] payload; }; /// 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). - public struct mavlink_gimbal_manager_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD. + public struct mavlink_can_frame_t { /// packet ordered constructor - public mavlink_gimbal_manager_status_t(uint time_boot_ms,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,byte primary_control_sysid,byte primary_control_compid,byte secondary_control_sysid,byte secondary_control_compid) + public mavlink_can_frame_t(uint id,byte target_system,byte target_component,byte bus,byte len,byte[] data) { - this.time_boot_ms = time_boot_ms; - this.flags = flags; - this.gimbal_device_id = gimbal_device_id; - this.primary_control_sysid = primary_control_sysid; - this.primary_control_compid = primary_control_compid; - this.secondary_control_sysid = secondary_control_sysid; - this.secondary_control_compid = secondary_control_compid; + this.id = id; + this.target_system = target_system; + this.target_component = target_component; + this.bus = bus; + this.len = len; + this.data = data; } /// packet xml order - public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,byte primary_control_sysid,byte primary_control_compid,byte secondary_control_sysid,byte secondary_control_compid) + public static mavlink_can_frame_t PopulateXMLOrder(byte target_system,byte target_component,byte bus,byte len,uint id,byte[] data) { - var msg = new mavlink_gimbal_manager_status_t(); + var msg = new mavlink_can_frame_t(); - msg.time_boot_ms = time_boot_ms; - msg.flags = flags; - msg.gimbal_device_id = gimbal_device_id; - msg.primary_control_sysid = primary_control_sysid; - msg.primary_control_compid = primary_control_compid; - msg.secondary_control_sysid = secondary_control_sysid; - msg.secondary_control_compid = secondary_control_compid; + msg.target_system = target_system; + msg.target_component = target_component; + msg.bus = bus; + msg.len = len; + msg.id = id; + msg.data = data; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Frame ID + [Units("")] + [Description("Frame ID")] //[FieldOffset(0)] - public uint time_boot_ms; + public uint id; - /// High level gimbal manager flags currently applied. GIMBAL_MANAGER_FLAGS bitmask + /// System ID. [Units("")] - [Description("High level gimbal manager flags currently applied.")] + [Description("System ID.")] //[FieldOffset(4)] - public /*GIMBAL_MANAGER_FLAGS*/uint flags; - - /// 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. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] - //[FieldOffset(8)] - public byte gimbal_device_id; + public byte target_system; - /// System ID of MAVLink component with primary control, 0 for none. + /// Component ID. [Units("")] - [Description("System ID of MAVLink component with primary control, 0 for none.")] - //[FieldOffset(9)] - public byte primary_control_sysid; + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; - /// Component ID of MAVLink component with primary control, 0 for none. + /// bus number [Units("")] - [Description("Component ID of MAVLink component with primary control, 0 for none.")] - //[FieldOffset(10)] - public byte primary_control_compid; + [Description("bus number")] + //[FieldOffset(6)] + public byte bus; - /// System ID of MAVLink component with secondary control, 0 for none. + /// Frame length [Units("")] - [Description("System ID of MAVLink component with secondary control, 0 for none.")] - //[FieldOffset(11)] - public byte secondary_control_sysid; + [Description("Frame length")] + //[FieldOffset(7)] + public byte len; - /// Component ID of MAVLink component with secondary control, 0 for none. + /// Frame data [Units("")] - [Description("Component ID of MAVLink component with secondary control, 0 for none.")] - //[FieldOffset(12)] - public byte secondary_control_compid; + [Description("Frame data")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] data; }; /// 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=72)] + /// A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling) + public struct mavlink_canfd_frame_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_canfd_frame_t(uint id,byte target_system,byte target_component,byte bus,byte len,byte[] data) { - 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.id = id; this.target_system = target_system; this.target_component = target_component; - this.gimbal_device_id = gimbal_device_id; + this.bus = bus; + this.len = len; + this.data = data; } /// 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_canfd_frame_t PopulateXMLOrder(byte target_system,byte target_component,byte bus,byte len,uint id,byte[] data) { - var msg = new mavlink_gimbal_manager_set_attitude_t(); + var msg = new mavlink_canfd_frame_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.bus = bus; + msg.len = len; + msg.id = id; + msg.data = data; return msg; } - /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS + /// Frame ID [Units("")] - [Description("High level gimbal manager flags to use.")] + [Description("Frame ID")] //[FieldOffset(0)] - public /*GIMBAL_MANAGER_FLAGS*/uint flags; + public uint id; - /// 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) + /// System ID. [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)")] + [Description("System ID.")] //[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; + public byte target_system; - /// 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; + /// Component ID. + [Units("")] + [Description("Component ID.")] + //[FieldOffset(5)] + public byte target_component; - /// System ID + /// bus number [Units("")] - [Description("System ID")] - //[FieldOffset(32)] - public byte target_system; + [Description("bus number")] + //[FieldOffset(6)] + public byte bus; - /// Component ID + /// Frame length [Units("")] - [Description("Component ID")] - //[FieldOffset(33)] - public byte target_component; + [Description("Frame length")] + //[FieldOffset(7)] + public byte len; - /// 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). + /// Frame data [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; + [Description("Frame data")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=64)] + public byte[] data; }; - /// 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 + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] + /// Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwith links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages. + public struct mavlink_can_filter_modify_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,byte gimbal_device_id) + public mavlink_can_filter_modify_t(ushort[] ids,byte target_system,byte target_component,byte bus,/*CAN_FILTER_OP*/byte operation,byte num_ids) { - this.uid = uid; - this.time_boot_ms = time_boot_ms; - this.firmware_version = firmware_version; - this.hardware_version = hardware_version; - this.roll_min = roll_min; - this.roll_max = roll_max; - this.pitch_min = pitch_min; - this.pitch_max = pitch_max; - this.yaw_min = yaw_min; - this.yaw_max = yaw_max; - this.cap_flags = cap_flags; - this.custom_cap_flags = custom_cap_flags; - this.vendor_name = vendor_name; - this.model_name = model_name; - this.custom_name = custom_name; - this.gimbal_device_id = gimbal_device_id; + this.ids = ids; + this.target_system = target_system; + this.target_component = target_component; + this.bus = bus; + this.operation = operation; + this.num_ids = num_ids; } /// 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,byte gimbal_device_id) + public static mavlink_can_filter_modify_t PopulateXMLOrder(byte target_system,byte target_component,byte bus,/*CAN_FILTER_OP*/byte operation,byte num_ids,ushort[] ids) { - var msg = new mavlink_gimbal_device_information_t(); + var msg = new mavlink_can_filter_modify_t(); - msg.time_boot_ms = time_boot_ms; - msg.vendor_name = vendor_name; - msg.model_name = model_name; - msg.custom_name = custom_name; - msg.firmware_version = firmware_version; - msg.hardware_version = hardware_version; - msg.uid = uid; - msg.cap_flags = cap_flags; - msg.custom_cap_flags = custom_cap_flags; - msg.roll_min = roll_min; - msg.roll_max = roll_max; - msg.pitch_min = pitch_min; - msg.pitch_max = pitch_max; - msg.yaw_min = yaw_min; - msg.yaw_max = yaw_max; - msg.gimbal_device_id = gimbal_device_id; + msg.target_system = target_system; + msg.target_component = target_component; + msg.bus = bus; + msg.operation = operation; + msg.num_ids = num_ids; + msg.ids = ids; return msg; } - /// UID of gimbal hardware (0 if unknown). + /// filter IDs, length num_ids [Units("")] - [Description("UID of gimbal hardware (0 if unknown).")] + [Description("filter IDs, length num_ids")] //[FieldOffset(0)] - public ulong uid; - - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] - //[FieldOffset(8)] - public uint time_boot_ms; - - /// Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - [Units("")] - [Description("Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).")] - //[FieldOffset(12)] - public uint firmware_version; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public ushort[] ids; - /// Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). + /// System ID. [Units("")] - [Description("Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).")] - //[FieldOffset(16)] - public uint hardware_version; - - /// 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). NAN if unknown.")] - //[FieldOffset(20)] - public float roll_min; - - /// 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). NAN if unknown.")] - //[FieldOffset(24)] - public float roll_max; - - /// Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] - [Units("[rad]")] - [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). NAN if unknown. [rad] - [Units("[rad]")] - [Description("Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] + [Description("System ID.")] //[FieldOffset(32)] - public float pitch_max; - - /// 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). NAN if unknown.")] - //[FieldOffset(36)] - public float yaw_min; - - /// 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). NAN if unknown.")] - //[FieldOffset(40)] - public float yaw_max; - - /// Bitmap of gimbal capability flags. GIMBAL_DEVICE_CAP_FLAGS bitmask - [Units("")] - [Description("Bitmap of gimbal capability flags.")] - //[FieldOffset(44)] - public /*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags; - - /// Bitmap for use for gimbal-specific capability flags. bitmask - [Units("")] - [Description("Bitmap for use for gimbal-specific capability flags.")] - //[FieldOffset(46)] - public ushort custom_cap_flags; + public byte target_system; - /// Name of the gimbal vendor. + /// Component ID. [Units("")] - [Description("Name of the gimbal vendor.")] - //[FieldOffset(48)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] vendor_name; + [Description("Component ID.")] + //[FieldOffset(33)] + public byte target_component; - /// Name of the gimbal model. + /// bus number [Units("")] - [Description("Name of the gimbal model.")] - //[FieldOffset(80)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] model_name; + [Description("bus number")] + //[FieldOffset(34)] + public byte bus; - /// Custom name of the gimbal given to it by the user. + /// what operation to perform on the filter list. See CAN_FILTER_OP enum. CAN_FILTER_OP [Units("")] - [Description("Custom name of the gimbal given to it by the user.")] - //[FieldOffset(112)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] custom_name; + [Description("what operation to perform on the filter list. See CAN_FILTER_OP enum.")] + //[FieldOffset(35)] + public /*CAN_FILTER_OP*/byte operation; - /// 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. + /// number of IDs in filter list [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; + [Description("number of IDs in filter list")] + //[FieldOffset(36)] + public byte num_ids; }; /// 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. 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 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=137)] + /// Cumulative distance traveled for each reported wheel. + public struct mavlink_wheel_distance_t { /// packet ordered constructor - public mavlink_gimbal_device_set_attitude_t(float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component) + public mavlink_wheel_distance_t(ulong time_usec,double[] distance,byte count) { - 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.flags = flags; - this.target_system = target_system; - this.target_component = target_component; + this.time_usec = time_usec; + this.distance = distance; + this.count = count; } /// packet xml order - public static mavlink_gimbal_device_set_attitude_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) + public static mavlink_wheel_distance_t PopulateXMLOrder(ulong time_usec,byte count,double[] distance) { - var msg = new mavlink_gimbal_device_set_attitude_t(); + var msg = new mavlink_wheel_distance_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.flags = flags; - 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.time_usec = time_usec; + msg.count = count; + msg.distance = distance; return msg; } - /// 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 described in the message description. Set fields to NaN to be ignored.")] + /// Timestamp (synced to UNIX time or since system boot). [us] + [Units("[us]")] + [Description("Timestamp (synced to UNIX time or since system boot).")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// 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: 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: 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: 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: 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: yawing to the right). The frame is described in the message description. NaN to be ignored.")] - //[FieldOffset(24)] - public float angular_velocity_z; - - /// Low level gimbal flags. GIMBAL_DEVICE_FLAGS bitmask - [Units("")] - [Description("Low level gimbal flags.")] - //[FieldOffset(28)] - public /*GIMBAL_DEVICE_FLAGS*/ushort flags; + public ulong time_usec; - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(30)] - public byte target_system; + /// Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. [m] + [Units("[m]")] + [Description("Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] + public double[] distance; - /// Component ID + /// Number of wheels reported. [Units("")] - [Description("Component ID")] - //[FieldOffset(31)] - public byte target_component; + [Description("Number of wheels reported.")] + //[FieldOffset(136)] + public byte count; }; - /// 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 + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] + /// Winch status. + public struct mavlink_winch_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,float delta_yaw,float delta_yaw_velocity,byte gimbal_device_id) + public mavlink_winch_status_t(ulong time_usec,float line_length,float speed,float tension,float voltage,float current,/*MAV_WINCH_STATUS_FLAG*/uint status,short temperature) { - this.time_boot_ms = time_boot_ms; - 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.failure_flags = failure_flags; - 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; + this.time_usec = time_usec; + this.line_length = line_length; + this.speed = speed; + this.tension = tension; + this.voltage = voltage; + this.current = current; + this.status = status; + this.temperature = temperature; } /// 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,float delta_yaw,float delta_yaw_velocity,byte gimbal_device_id) + public static mavlink_winch_status_t PopulateXMLOrder(ulong time_usec,float line_length,float speed,float tension,float voltage,float current,short temperature,/*MAV_WINCH_STATUS_FLAG*/uint status) { - var msg = new mavlink_gimbal_device_attitude_status_t(); + var msg = new mavlink_winch_status_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.time_boot_ms = time_boot_ms; - msg.flags = flags; - 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.failure_flags = failure_flags; - msg.delta_yaw = delta_yaw; - msg.delta_yaw_velocity = delta_yaw_velocity; - msg.gimbal_device_id = gimbal_device_id; + msg.time_usec = time_usec; + msg.line_length = line_length; + msg.speed = speed; + msg.tension = tension; + msg.voltage = voltage; + msg.current = current; + msg.temperature = temperature; + msg.status = status; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Timestamp (synced to UNIX time or since system boot). [us] + [Units("[us]")] + [Description("Timestamp (synced to UNIX time or since system boot).")] //[FieldOffset(0)] - public uint time_boot_ms; + public ulong time_usec; - /// 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 described in the message description.")] - //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; + /// Length of line released. NaN if unknown [m] + [Units("[m]")] + [Description("Length of line released. NaN if unknown")] + //[FieldOffset(8)] + public float line_length; - /// 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 (positive: rolling to the right). The frame is described in the message description. NaN if unknown.")] + /// Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown [m/s] + [Units("[m/s]")] + [Description("Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown")] + //[FieldOffset(12)] + public float speed; + + /// Tension on the line. NaN if unknown [kg] + [Units("[kg]")] + [Description("Tension on the line. NaN if unknown")] + //[FieldOffset(16)] + public float tension; + + /// Voltage of the battery supplying the winch. NaN if unknown [V] + [Units("[V]")] + [Description("Voltage of the battery supplying the winch. NaN if unknown")] //[FieldOffset(20)] - public float angular_velocity_x; + public float voltage; - /// 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 (positive: pitching up). The frame is described in the message description. NaN if unknown.")] + /// Current draw from the winch. NaN if unknown [A] + [Units("[A]")] + [Description("Current draw from the winch. NaN if unknown")] //[FieldOffset(24)] - public float angular_velocity_y; + public float current; - /// 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 (positive: yawing to the right). The frame is described in the message description. NaN if unknown.")] + /// Status flags MAV_WINCH_STATUS_FLAG bitmask + [Units("")] + [Description("Status flags")] //[FieldOffset(28)] - public float angular_velocity_z; + public /*MAV_WINCH_STATUS_FLAG*/uint status; - /// Failure flags (0 for no failure) GIMBAL_DEVICE_ERROR_FLAGS bitmask - [Units("")] - [Description("Failure flags (0 for no failure)")] + /// Temperature of the motor. INT16_MAX if unknown [degC] + [Units("[degC]")] + [Description("Temperature of the motor. INT16_MAX if unknown")] //[FieldOffset(32)] - public /*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags; - - /// Current gimbal flags set. GIMBAL_DEVICE_FLAGS bitmask - [Units("")] - [Description("Current gimbal flags set.")] - //[FieldOffset(36)] - public /*GIMBAL_DEVICE_FLAGS*/ushort flags; - - /// System ID - [Units("")] - [Description("System ID")] - //[FieldOffset(38)] - public byte target_system; - - /// Component ID - [Units("")] - [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; + public short temperature; }; - - /// 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 + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html. + public struct mavlink_open_drone_id_basic_id_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,float angular_velocity_z) + public mavlink_open_drone_id_basic_id_t(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_ID_TYPE*/byte id_type,/*MAV_ODID_UA_TYPE*/byte ua_type,byte[] uas_id) { - this.time_boot_us = time_boot_us; - this.q = q; - this.q_estimated_delay_us = q_estimated_delay_us; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.v_estimated_delay_us = v_estimated_delay_us; - this.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; - this.estimator_status = estimator_status; this.target_system = target_system; this.target_component = target_component; - this.landed_state = landed_state; - this.angular_velocity_z = angular_velocity_z; + this.id_or_mac = id_or_mac; + this.id_type = id_type; + this.ua_type = ua_type; + this.uas_id = uas_id; } /// 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,float angular_velocity_z) + public static mavlink_open_drone_id_basic_id_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_ID_TYPE*/byte id_type,/*MAV_ODID_UA_TYPE*/byte ua_type,byte[] uas_id) { - var msg = new mavlink_autopilot_state_for_gimbal_device_t(); + var msg = new mavlink_open_drone_id_basic_id_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.time_boot_us = time_boot_us; - msg.q = q; - msg.q_estimated_delay_us = q_estimated_delay_us; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.v_estimated_delay_us = v_estimated_delay_us; - 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; + msg.id_or_mac = id_or_mac; + msg.id_type = id_type; + msg.ua_type = ua_type; + msg.uas_id = uas_id; return msg; } - /// Timestamp (time since system boot). [us] - [Units("[us]")] - [Description("Timestamp (time since system boot).")] + /// System ID (0 for broadcast). + [Units("")] + [Description("System ID (0 for broadcast).")] //[FieldOffset(0)] - public ulong time_boot_us; + public byte target_system; - /// Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). + /// Component ID (0 for broadcast). [Units("")] - [Description("Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; - - /// Estimated delay of the attitude data. 0 if unknown. [us] - [Units("[us]")] - [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). NAN if unknown. [m/s] - [Units("[m/s]")] - [Description("X Speed in NED (North, East, Down). NAN if unknown.")] - //[FieldOffset(28)] - public float vx; - - /// Y Speed in NED (North, East, Down). NAN if unknown. [m/s] - [Units("[m/s]")] - [Description("Y Speed in NED (North, East, Down). NAN if unknown.")] - //[FieldOffset(32)] - public float vy; - - /// Z Speed in NED (North, East, Down). NAN if unknown. [m/s] - [Units("[m/s]")] - [Description("Z Speed in NED (North, East, Down). NAN if unknown.")] - //[FieldOffset(36)] - public float vz; - - /// Estimated delay of the speed data. 0 if unknown. [us] - [Units("[us]")] - [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: 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: 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; + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(1)] + public byte target_component; - /// Bitmap indicating which estimator outputs are valid. ESTIMATOR_STATUS_FLAGS bitmask + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. [Units("")] - [Description("Bitmap indicating which estimator outputs are valid.")] - //[FieldOffset(48)] - public /*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status; + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; - /// System ID + /// Indicates the format for the uas_id field of this message. MAV_ODID_ID_TYPE [Units("")] - [Description("System ID")] - //[FieldOffset(50)] - public byte target_system; + [Description("Indicates the format for the uas_id field of this message.")] + //[FieldOffset(22)] + public /*MAV_ODID_ID_TYPE*/byte id_type; - /// Component ID + /// Indicates the type of UA (Unmanned Aircraft). MAV_ODID_UA_TYPE [Units("")] - [Description("Component ID")] - //[FieldOffset(51)] - public byte target_component; + [Description("Indicates the type of UA (Unmanned Aircraft).")] + //[FieldOffset(23)] + public /*MAV_ODID_UA_TYPE*/byte ua_type; - /// The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. MAV_LANDED_STATE + /// UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. [Units("")] - [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; + [Description("UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] uas_id; }; - + [Obsolete] /// extensions_start 0 - [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 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=59)] + /// Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft. + public struct mavlink_open_drone_id_location_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_open_drone_id_location_t(int latitude,int longitude,float altitude_barometric,float altitude_geodetic,float height,float timestamp,ushort direction,ushort speed_horizontal,short speed_vertical,byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_STATUS*/byte status,/*MAV_ODID_HEIGHT_REF*/byte height_reference,/*MAV_ODID_HOR_ACC*/byte horizontal_accuracy,/*MAV_ODID_VER_ACC*/byte vertical_accuracy,/*MAV_ODID_VER_ACC*/byte barometer_accuracy,/*MAV_ODID_SPEED_ACC*/byte speed_accuracy,/*MAV_ODID_TIME_ACC*/byte timestamp_accuracy) { - this.flags = flags; - this.pitch = pitch; - this.yaw = yaw; - this.pitch_rate = pitch_rate; - this.yaw_rate = yaw_rate; + this.latitude = latitude; + this.longitude = longitude; + this.altitude_barometric = altitude_barometric; + this.altitude_geodetic = altitude_geodetic; + this.height = height; + this.timestamp = timestamp; + this.direction = direction; + this.speed_horizontal = speed_horizontal; + this.speed_vertical = speed_vertical; this.target_system = target_system; this.target_component = target_component; - this.gimbal_device_id = gimbal_device_id; + this.id_or_mac = id_or_mac; + this.status = status; + this.height_reference = height_reference; + this.horizontal_accuracy = horizontal_accuracy; + this.vertical_accuracy = vertical_accuracy; + this.barometer_accuracy = barometer_accuracy; + this.speed_accuracy = speed_accuracy; + this.timestamp_accuracy = timestamp_accuracy; } /// 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_open_drone_id_location_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_STATUS*/byte status,ushort direction,ushort speed_horizontal,short speed_vertical,int latitude,int longitude,float altitude_barometric,float altitude_geodetic,/*MAV_ODID_HEIGHT_REF*/byte height_reference,float height,/*MAV_ODID_HOR_ACC*/byte horizontal_accuracy,/*MAV_ODID_VER_ACC*/byte vertical_accuracy,/*MAV_ODID_VER_ACC*/byte barometer_accuracy,/*MAV_ODID_SPEED_ACC*/byte speed_accuracy,float timestamp,/*MAV_ODID_TIME_ACC*/byte timestamp_accuracy) { - var msg = new mavlink_gimbal_manager_set_pitchyaw_t(); + var msg = new mavlink_open_drone_id_location_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.id_or_mac = id_or_mac; + msg.status = status; + msg.direction = direction; + msg.speed_horizontal = speed_horizontal; + msg.speed_vertical = speed_vertical; + msg.latitude = latitude; + msg.longitude = longitude; + msg.altitude_barometric = altitude_barometric; + msg.altitude_geodetic = altitude_geodetic; + msg.height_reference = height_reference; + msg.height = height; + msg.horizontal_accuracy = horizontal_accuracy; + msg.vertical_accuracy = vertical_accuracy; + msg.barometer_accuracy = barometer_accuracy; + msg.speed_accuracy = speed_accuracy; + msg.timestamp = timestamp; + msg.timestamp_accuracy = timestamp_accuracy; + + return msg; + } + + + /// Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). [degE7] + [Units("[degE7]")] + [Description("Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).")] + //[FieldOffset(0)] + public int latitude; + + /// Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). [degE7] + [Units("[degE7]")] + [Description("Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).")] + //[FieldOffset(4)] + public int longitude; + + /// The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. [m] + [Units("[m]")] + [Description("The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.")] + //[FieldOffset(8)] + public float altitude_barometric; + + /// The geodetic altitude as defined by WGS84. If unknown: -1000 m. [m] + [Units("[m]")] + [Description("The geodetic altitude as defined by WGS84. If unknown: -1000 m.")] + //[FieldOffset(12)] + public float altitude_geodetic; + + /// The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. [m] + [Units("[m]")] + [Description("The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.")] + //[FieldOffset(16)] + public float height; + + /// Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. [s] + [Units("[s]")] + [Description("Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF.")] + //[FieldOffset(20)] + public float timestamp; + + /// Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. [cdeg] + [Units("[cdeg]")] + [Description("Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.")] + //[FieldOffset(24)] + public ushort direction; + + /// Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. [cm/s] + [Units("[cm/s]")] + [Description("Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.")] + //[FieldOffset(26)] + public ushort speed_horizontal; + + /// The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. [cm/s] + [Units("[cm/s]")] + [Description("The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.")] + //[FieldOffset(28)] + public short speed_vertical; + + /// System ID (0 for broadcast). + [Units("")] + [Description("System ID (0 for broadcast).")] + //[FieldOffset(30)] + public byte target_system; - msg.target_system = target_system; - msg.target_component = target_component; - msg.flags = flags; - msg.gimbal_device_id = gimbal_device_id; - msg.pitch = pitch; - msg.yaw = yaw; - msg.pitch_rate = pitch_rate; - msg.yaw_rate = yaw_rate; - - return msg; - } - + /// Component ID (0 for broadcast). + [Units("")] + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(31)] + public byte target_component; - /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. [Units("")] - [Description("High level gimbal manager flags to use.")] - //[FieldOffset(0)] - public /*GIMBAL_MANAGER_FLAGS*/uint flags; + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; - /// 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)] - public float pitch; + /// Indicates whether the unmanned aircraft is on the ground or in the air. MAV_ODID_STATUS + [Units("")] + [Description("Indicates whether the unmanned aircraft is on the ground or in the air.")] + //[FieldOffset(52)] + public /*MAV_ODID_STATUS*/byte status; - /// 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; + /// Indicates the reference point for the height field. MAV_ODID_HEIGHT_REF + [Units("")] + [Description("Indicates the reference point for the height field.")] + //[FieldOffset(53)] + public /*MAV_ODID_HEIGHT_REF*/byte height_reference; - /// 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).")] - //[FieldOffset(12)] - public float pitch_rate; + /// The accuracy of the horizontal position. MAV_ODID_HOR_ACC + [Units("")] + [Description("The accuracy of the horizontal position.")] + //[FieldOffset(54)] + public /*MAV_ODID_HOR_ACC*/byte horizontal_accuracy; - /// 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).")] - //[FieldOffset(16)] - public float yaw_rate; + /// The accuracy of the vertical position. MAV_ODID_VER_ACC + [Units("")] + [Description("The accuracy of the vertical position.")] + //[FieldOffset(55)] + public /*MAV_ODID_VER_ACC*/byte vertical_accuracy; - /// System ID + /// The accuracy of the barometric altitude. MAV_ODID_VER_ACC [Units("")] - [Description("System ID")] - //[FieldOffset(20)] - public byte target_system; + [Description("The accuracy of the barometric altitude.")] + //[FieldOffset(56)] + public /*MAV_ODID_VER_ACC*/byte barometer_accuracy; - /// Component ID + /// The accuracy of the horizontal and vertical speed. MAV_ODID_SPEED_ACC [Units("")] - [Description("Component ID")] - //[FieldOffset(21)] - public byte target_component; + [Description("The accuracy of the horizontal and vertical speed.")] + //[FieldOffset(57)] + public /*MAV_ODID_SPEED_ACC*/byte speed_accuracy; - /// 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). + /// The accuracy of the timestamps. MAV_ODID_TIME_ACC [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(22)] - public byte gimbal_device_id; + [Description("The accuracy of the timestamps.")] + //[FieldOffset(58)] + public /*MAV_ODID_TIME_ACC*/byte timestamp_accuracy; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] - /// 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 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] + /// Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes. + public struct mavlink_open_drone_id_authentication_t { /// packet ordered constructor - 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) + public mavlink_open_drone_id_authentication_t(uint timestamp,byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_AUTH_TYPE*/byte authentication_type,byte data_page,byte last_page_index,byte length,byte[] authentication_data) { - this.flags = flags; - this.pitch = pitch; - this.yaw = yaw; - this.pitch_rate = pitch_rate; - this.yaw_rate = yaw_rate; + this.timestamp = timestamp; this.target_system = target_system; this.target_component = target_component; - this.gimbal_device_id = gimbal_device_id; + this.id_or_mac = id_or_mac; + this.authentication_type = authentication_type; + this.data_page = data_page; + this.last_page_index = last_page_index; + this.length = length; + this.authentication_data = authentication_data; } /// packet xml order - 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) + public static mavlink_open_drone_id_authentication_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_AUTH_TYPE*/byte authentication_type,byte data_page,byte last_page_index,byte length,uint timestamp,byte[] authentication_data) { - var msg = new mavlink_gimbal_manager_set_manual_control_t(); + var msg = new mavlink_open_drone_id_authentication_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.flags = flags; - msg.gimbal_device_id = gimbal_device_id; - msg.pitch = pitch; - msg.yaw = yaw; - msg.pitch_rate = pitch_rate; - msg.yaw_rate = yaw_rate; + msg.id_or_mac = id_or_mac; + msg.authentication_type = authentication_type; + msg.data_page = data_page; + msg.last_page_index = last_page_index; + msg.length = length; + msg.timestamp = timestamp; + msg.authentication_data = authentication_data; return msg; } - /// High level gimbal manager flags. GIMBAL_MANAGER_FLAGS - [Units("")] - [Description("High level gimbal manager flags.")] + /// This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. [s] + [Units("[s]")] + [Description("This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.")] //[FieldOffset(0)] - public /*GIMBAL_MANAGER_FLAGS*/uint flags; + public uint timestamp; - /// Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). + /// System ID (0 for broadcast). [Units("")] - [Description("Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).")] + [Description("System ID (0 for broadcast).")] //[FieldOffset(4)] - public float pitch; + public byte target_system; - /// Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + /// Component ID (0 for broadcast). [Units("")] - [Description("Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).")] - //[FieldOffset(8)] - public float yaw; + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(5)] + public byte target_component; - /// Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. [Units("")] - [Description("Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).")] - //[FieldOffset(12)] - public float pitch_rate; + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; - /// Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + /// Indicates the type of authentication. MAV_ODID_AUTH_TYPE [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; + [Description("Indicates the type of authentication.")] + //[FieldOffset(26)] + public /*MAV_ODID_AUTH_TYPE*/byte authentication_type; - /// System ID + /// Allowed range is 0 - 15. [Units("")] - [Description("System ID")] - //[FieldOffset(20)] - public byte target_system; + [Description("Allowed range is 0 - 15.")] + //[FieldOffset(27)] + public byte data_page; - /// Component ID + /// This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. [Units("")] - [Description("Component ID")] - //[FieldOffset(21)] - public byte target_component; + [Description("This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.")] + //[FieldOffset(28)] + public byte last_page_index; - /// 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). + /// This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. [bytes] + [Units("[bytes]")] + [Description("This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.")] + //[FieldOffset(29)] + public byte length; + + /// Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. [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(22)] - public byte gimbal_device_id; + [Description("Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.")] + //[FieldOffset(30)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=23)] + public byte[] authentication_data; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=96)] - /// Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE - public struct mavlink_wifi_config_ap_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] + /// Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation. + public struct mavlink_open_drone_id_self_id_t { /// packet ordered constructor - public mavlink_wifi_config_ap_t(byte[] ssid,byte[] password) + public mavlink_open_drone_id_self_id_t(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_DESC_TYPE*/byte description_type,byte[] description) { - this.ssid = ssid; - this.password = password; + this.target_system = target_system; + this.target_component = target_component; + this.id_or_mac = id_or_mac; + this.description_type = description_type; + this.description = description; } /// packet xml order - public static mavlink_wifi_config_ap_t PopulateXMLOrder(byte[] ssid,byte[] password) + public static mavlink_open_drone_id_self_id_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_DESC_TYPE*/byte description_type,byte[] description) { - var msg = new mavlink_wifi_config_ap_t(); + var msg = new mavlink_open_drone_id_self_id_t(); - msg.ssid = ssid; - msg.password = password; + msg.target_system = target_system; + msg.target_component = target_component; + msg.id_or_mac = id_or_mac; + msg.description_type = description_type; + msg.description = description; return msg; } - /// Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. + /// System ID (0 for broadcast). [Units("")] - [Description("Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.")] + [Description("System ID (0 for broadcast).")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] ssid; + public byte target_system; - /// Password. Blank for an open AP. MD5 hash when message is sent back as a response. + /// Component ID (0 for broadcast). [Units("")] - [Description("Password. Blank for an open AP. MD5 hash when message is sent back as a response.")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=64)] - public byte[] password; + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(1)] + public byte target_component; + + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + [Units("")] + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; + + /// Indicates the type of the description field. MAV_ODID_DESC_TYPE + [Units("")] + [Description("Indicates the type of the description field.")] + //[FieldOffset(22)] + public /*MAV_ODID_DESC_TYPE*/byte description_type; + + /// Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. + [Units("")] + [Description("Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.")] + //[FieldOffset(23)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=23)] + public byte[] description; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=58)] - /// The location and information of an AIS vessel - public struct mavlink_ais_vessel_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] + /// Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information. + public struct mavlink_open_drone_id_system_t { /// packet ordered constructor - public mavlink_ais_vessel_t(uint MMSI,int lat,int lon,ushort COG,ushort heading,ushort velocity,ushort dimension_bow,ushort dimension_stern,ushort tslc,/*AIS_FLAGS*/ushort flags,sbyte turn_rate,/*AIS_NAV_STATUS*/byte navigational_status,/*AIS_TYPE*/byte type,byte dimension_port,byte dimension_starboard,byte[] callsign,byte[] name) + public mavlink_open_drone_id_system_t(int operator_latitude,int operator_longitude,float area_ceiling,float area_floor,float operator_altitude_geo,uint timestamp,ushort area_count,ushort area_radius,byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_LOCATION_TYPE*/byte operator_location_type,/*MAV_ODID_CLASSIFICATION_TYPE*/byte classification_type,/*MAV_ODID_CATEGORY_EU*/byte category_eu,/*MAV_ODID_CLASS_EU*/byte class_eu) { - this.MMSI = MMSI; - this.lat = lat; - this.lon = lon; - this.COG = COG; - this.heading = heading; - this.velocity = velocity; - this.dimension_bow = dimension_bow; - this.dimension_stern = dimension_stern; - this.tslc = tslc; - this.flags = flags; - this.turn_rate = turn_rate; - this.navigational_status = navigational_status; - this.type = type; - this.dimension_port = dimension_port; - this.dimension_starboard = dimension_starboard; - this.callsign = callsign; - this.name = name; + this.operator_latitude = operator_latitude; + this.operator_longitude = operator_longitude; + this.area_ceiling = area_ceiling; + this.area_floor = area_floor; + this.operator_altitude_geo = operator_altitude_geo; + this.timestamp = timestamp; + this.area_count = area_count; + this.area_radius = area_radius; + this.target_system = target_system; + this.target_component = target_component; + this.id_or_mac = id_or_mac; + this.operator_location_type = operator_location_type; + this.classification_type = classification_type; + this.category_eu = category_eu; + this.class_eu = class_eu; } /// packet xml order - public static mavlink_ais_vessel_t PopulateXMLOrder(uint MMSI,int lat,int lon,ushort COG,ushort heading,ushort velocity,sbyte turn_rate,/*AIS_NAV_STATUS*/byte navigational_status,/*AIS_TYPE*/byte type,ushort dimension_bow,ushort dimension_stern,byte dimension_port,byte dimension_starboard,byte[] callsign,byte[] name,ushort tslc,/*AIS_FLAGS*/ushort flags) + public static mavlink_open_drone_id_system_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_LOCATION_TYPE*/byte operator_location_type,/*MAV_ODID_CLASSIFICATION_TYPE*/byte classification_type,int operator_latitude,int operator_longitude,ushort area_count,ushort area_radius,float area_ceiling,float area_floor,/*MAV_ODID_CATEGORY_EU*/byte category_eu,/*MAV_ODID_CLASS_EU*/byte class_eu,float operator_altitude_geo,uint timestamp) { - var msg = new mavlink_ais_vessel_t(); + var msg = new mavlink_open_drone_id_system_t(); - msg.MMSI = MMSI; - msg.lat = lat; - msg.lon = lon; - msg.COG = COG; - msg.heading = heading; - msg.velocity = velocity; - msg.turn_rate = turn_rate; - msg.navigational_status = navigational_status; - msg.type = type; - msg.dimension_bow = dimension_bow; - msg.dimension_stern = dimension_stern; - msg.dimension_port = dimension_port; - msg.dimension_starboard = dimension_starboard; - msg.callsign = callsign; - msg.name = name; - msg.tslc = tslc; - msg.flags = flags; + msg.target_system = target_system; + msg.target_component = target_component; + msg.id_or_mac = id_or_mac; + msg.operator_location_type = operator_location_type; + msg.classification_type = classification_type; + msg.operator_latitude = operator_latitude; + msg.operator_longitude = operator_longitude; + msg.area_count = area_count; + msg.area_radius = area_radius; + msg.area_ceiling = area_ceiling; + msg.area_floor = area_floor; + msg.category_eu = category_eu; + msg.class_eu = class_eu; + msg.operator_altitude_geo = operator_altitude_geo; + msg.timestamp = timestamp; return msg; } - /// Mobile Marine Service Identifier, 9 decimal digits - [Units("")] - [Description("Mobile Marine Service Identifier, 9 decimal digits")] + /// Latitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] + [Units("[degE7]")] + [Description("Latitude of the operator. If unknown: 0 (both Lat/Lon).")] //[FieldOffset(0)] - public uint MMSI; + public int operator_latitude; - /// Latitude [degE7] + /// Longitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] [Units("[degE7]")] - [Description("Latitude")] + [Description("Longitude of the operator. If unknown: 0 (both Lat/Lon).")] //[FieldOffset(4)] - public int lat; + public int operator_longitude; - /// Longitude [degE7] - [Units("[degE7]")] - [Description("Longitude")] + /// Area Operations Ceiling relative to WGS84. If unknown: -1000 m. [m] + [Units("[m]")] + [Description("Area Operations Ceiling relative to WGS84. If unknown: -1000 m.")] //[FieldOffset(8)] - public int lon; - - /// Course over ground [cdeg] - [Units("[cdeg]")] - [Description("Course over ground")] - //[FieldOffset(12)] - public ushort COG; - - /// True heading [cdeg] - [Units("[cdeg]")] - [Description("True heading")] - //[FieldOffset(14)] - public ushort heading; - - /// Speed over ground [cm/s] - [Units("[cm/s]")] - [Description("Speed over ground")] - //[FieldOffset(16)] - public ushort velocity; + public float area_ceiling; - /// Distance from lat/lon location to bow [m] + /// Area Operations Floor relative to WGS84. If unknown: -1000 m. [m] [Units("[m]")] - [Description("Distance from lat/lon location to bow")] - //[FieldOffset(18)] - public ushort dimension_bow; + [Description("Area Operations Floor relative to WGS84. If unknown: -1000 m.")] + //[FieldOffset(12)] + public float area_floor; - /// Distance from lat/lon location to stern [m] + /// Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. [m] [Units("[m]")] - [Description("Distance from lat/lon location to stern")] - //[FieldOffset(20)] - public ushort dimension_stern; + [Description("Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.")] + //[FieldOffset(16)] + public float operator_altitude_geo; - /// Time since last communication in seconds [s] + /// 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. [s] [Units("[s]")] - [Description("Time since last communication in seconds")] - //[FieldOffset(22)] - public ushort tslc; + [Description("32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.")] + //[FieldOffset(20)] + public uint timestamp; - /// Bitmask to indicate various statuses including valid data fields AIS_FLAGS bitmask + /// Number of aircraft in the area, group or formation (default 1). [Units("")] - [Description("Bitmask to indicate various statuses including valid data fields")] + [Description("Number of aircraft in the area, group or formation (default 1).")] //[FieldOffset(24)] - public /*AIS_FLAGS*/ushort flags; + public ushort area_count; - /// Turn rate [cdeg/s] - [Units("[cdeg/s]")] - [Description("Turn rate")] + /// Radius of the cylindrical area of the group or formation (default 0). [m] + [Units("[m]")] + [Description("Radius of the cylindrical area of the group or formation (default 0).")] //[FieldOffset(26)] - public sbyte turn_rate; - - /// Navigational status AIS_NAV_STATUS - [Units("")] - [Description("Navigational status")] - //[FieldOffset(27)] - public /*AIS_NAV_STATUS*/byte navigational_status; + public ushort area_radius; - /// Type of vessels AIS_TYPE + /// System ID (0 for broadcast). [Units("")] - [Description("Type of vessels")] + [Description("System ID (0 for broadcast).")] //[FieldOffset(28)] - public /*AIS_TYPE*/byte type; + public byte target_system; - /// Distance from lat/lon location to port side [m] - [Units("[m]")] - [Description("Distance from lat/lon location to port side")] + /// Component ID (0 for broadcast). + [Units("")] + [Description("Component ID (0 for broadcast).")] //[FieldOffset(29)] - public byte dimension_port; + public byte target_component; - /// Distance from lat/lon location to starboard side [m] - [Units("[m]")] - [Description("Distance from lat/lon location to starboard side")] + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + [Units("")] + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] //[FieldOffset(30)] - public byte dimension_starboard; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; - /// The vessel callsign + /// Specifies the operator location type. MAV_ODID_OPERATOR_LOCATION_TYPE [Units("")] - [Description("The vessel callsign")] - //[FieldOffset(31)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=7)] - public byte[] callsign; + [Description("Specifies the operator location type.")] + //[FieldOffset(50)] + public /*MAV_ODID_OPERATOR_LOCATION_TYPE*/byte operator_location_type; - /// The vessel name + /// Specifies the classification type of the UA. MAV_ODID_CLASSIFICATION_TYPE [Units("")] - [Description("The vessel name")] - //[FieldOffset(38)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] name; + [Description("Specifies the classification type of the UA.")] + //[FieldOffset(51)] + public /*MAV_ODID_CLASSIFICATION_TYPE*/byte classification_type; + + /// When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. MAV_ODID_CATEGORY_EU + [Units("")] + [Description("When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.")] + //[FieldOffset(52)] + public /*MAV_ODID_CATEGORY_EU*/byte category_eu; + + /// When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. MAV_ODID_CLASS_EU + [Units("")] + [Description("When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.")] + //[FieldOffset(53)] + public /*MAV_ODID_CLASS_EU*/byte class_eu; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] - /// General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message 'uavcan.protocol.NodeStatus' for the background information. The UAVCAN specification is available at http://uavcan.org. - public struct mavlink_uavcan_node_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=43)] + /// Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID. + public struct mavlink_open_drone_id_operator_id_t { /// packet ordered constructor - public mavlink_uavcan_node_status_t(ulong time_usec,uint uptime_sec,ushort vendor_specific_status_code,/*UAVCAN_NODE_HEALTH*/byte health,/*UAVCAN_NODE_MODE*/byte mode,byte sub_mode) + public mavlink_open_drone_id_operator_id_t(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_ID_TYPE*/byte operator_id_type,byte[] operator_id) { - this.time_usec = time_usec; - this.uptime_sec = uptime_sec; - this.vendor_specific_status_code = vendor_specific_status_code; - this.health = health; - this.mode = mode; - this.sub_mode = sub_mode; + this.target_system = target_system; + this.target_component = target_component; + this.id_or_mac = id_or_mac; + this.operator_id_type = operator_id_type; + this.operator_id = operator_id; } /// packet xml order - public static mavlink_uavcan_node_status_t PopulateXMLOrder(ulong time_usec,uint uptime_sec,/*UAVCAN_NODE_HEALTH*/byte health,/*UAVCAN_NODE_MODE*/byte mode,byte sub_mode,ushort vendor_specific_status_code) + public static mavlink_open_drone_id_operator_id_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_ID_TYPE*/byte operator_id_type,byte[] operator_id) { - var msg = new mavlink_uavcan_node_status_t(); + var msg = new mavlink_open_drone_id_operator_id_t(); - msg.time_usec = time_usec; - msg.uptime_sec = uptime_sec; - msg.health = health; - msg.mode = mode; - msg.sub_mode = sub_mode; - msg.vendor_specific_status_code = vendor_specific_status_code; + msg.target_system = target_system; + msg.target_component = target_component; + msg.id_or_mac = id_or_mac; + msg.operator_id_type = operator_id_type; + msg.operator_id = operator_id; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// System ID (0 for broadcast). + [Units("")] + [Description("System ID (0 for broadcast).")] //[FieldOffset(0)] - public ulong time_usec; - - /// Time since the start-up of the node. [s] - [Units("[s]")] - [Description("Time since the start-up of the node.")] - //[FieldOffset(8)] - public uint uptime_sec; + public byte target_system; - /// Vendor-specific status information. + /// Component ID (0 for broadcast). [Units("")] - [Description("Vendor-specific status information.")] - //[FieldOffset(12)] - public ushort vendor_specific_status_code; + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(1)] + public byte target_component; - /// Generalized node health status. UAVCAN_NODE_HEALTH + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. [Units("")] - [Description("Generalized node health status.")] - //[FieldOffset(14)] - public /*UAVCAN_NODE_HEALTH*/byte health; + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] + //[FieldOffset(2)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; - /// Generalized operating mode. UAVCAN_NODE_MODE + /// Indicates the type of the operator_id field. MAV_ODID_OPERATOR_ID_TYPE [Units("")] - [Description("Generalized operating mode.")] - //[FieldOffset(15)] - public /*UAVCAN_NODE_MODE*/byte mode; + [Description("Indicates the type of the operator_id field.")] + //[FieldOffset(22)] + public /*MAV_ODID_OPERATOR_ID_TYPE*/byte operator_id_type; - /// Not used currently. + /// Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. [Units("")] - [Description("Not used currently.")] - //[FieldOffset(16)] - public byte sub_mode; + [Description("Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.")] + //[FieldOffset(23)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] operator_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=116)] - /// General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service 'uavcan.protocol.GetNodeInfo' for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at http://uavcan.org. - public struct mavlink_uavcan_node_info_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] + /// Status from the transmitter telling the flight controller if the remote ID system is ready for arming. + public struct mavlink_open_drone_id_arm_status_t { /// packet ordered constructor - public mavlink_uavcan_node_info_t(ulong time_usec,uint uptime_sec,uint sw_vcs_commit,byte[] name,byte hw_version_major,byte hw_version_minor,byte[] hw_unique_id,byte sw_version_major,byte sw_version_minor) + public mavlink_open_drone_id_arm_status_t(/*MAV_ODID_ARM_STATUS*/byte status,byte[] error) { - this.time_usec = time_usec; - this.uptime_sec = uptime_sec; - this.sw_vcs_commit = sw_vcs_commit; - this.name = name; - this.hw_version_major = hw_version_major; - this.hw_version_minor = hw_version_minor; - this.hw_unique_id = hw_unique_id; - this.sw_version_major = sw_version_major; - this.sw_version_minor = sw_version_minor; + this.status = status; + this.error = error; } /// packet xml order - public static mavlink_uavcan_node_info_t PopulateXMLOrder(ulong time_usec,uint uptime_sec,byte[] name,byte hw_version_major,byte hw_version_minor,byte[] hw_unique_id,byte sw_version_major,byte sw_version_minor,uint sw_vcs_commit) + public static mavlink_open_drone_id_arm_status_t PopulateXMLOrder(/*MAV_ODID_ARM_STATUS*/byte status,byte[] error) { - var msg = new mavlink_uavcan_node_info_t(); + var msg = new mavlink_open_drone_id_arm_status_t(); - msg.time_usec = time_usec; - msg.uptime_sec = uptime_sec; - msg.name = name; - msg.hw_version_major = hw_version_major; - msg.hw_version_minor = hw_version_minor; - msg.hw_unique_id = hw_unique_id; - msg.sw_version_major = sw_version_major; - msg.sw_version_minor = sw_version_minor; - msg.sw_vcs_commit = sw_vcs_commit; + msg.status = status; + msg.error = error; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] - //[FieldOffset(0)] - public ulong time_usec; - - /// Time since the start-up of the node. [s] - [Units("[s]")] - [Description("Time since the start-up of the node.")] - //[FieldOffset(8)] - public uint uptime_sec; - - /// Version control system (VCS) revision identifier (e.g. git short commit hash). Zero if unknown. - [Units("")] - [Description("Version control system (VCS) revision identifier (e.g. git short commit hash). Zero if unknown.")] - //[FieldOffset(12)] - public uint sw_vcs_commit; - - /// Node name string. For example, 'sapog.px4.io'. - [Units("")] - [Description("Node name string. For example, 'sapog.px4.io'.")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=80)] - public byte[] name; - - /// Hardware major version number. - [Units("")] - [Description("Hardware major version number.")] - //[FieldOffset(96)] - public byte hw_version_major; - - /// Hardware minor version number. - [Units("")] - [Description("Hardware minor version number.")] - //[FieldOffset(97)] - public byte hw_version_minor; - - /// Hardware unique 128-bit ID. - [Units("")] - [Description("Hardware unique 128-bit ID.")] - //[FieldOffset(98)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] hw_unique_id; - - /// Software major version number. + /// Status level indicating if arming is allowed. MAV_ODID_ARM_STATUS [Units("")] - [Description("Software major version number.")] - //[FieldOffset(114)] - public byte sw_version_major; + [Description("Status level indicating if arming is allowed.")] + //[FieldOffset(0)] + public /*MAV_ODID_ARM_STATUS*/byte status; - /// Software minor version number. + /// Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. [Units("")] - [Description("Software minor version number.")] - //[FieldOffset(115)] - public byte sw_version_minor; + [Description("Text error message, should be empty if status is good to arm. Fill with nulls in unused portion.")] + //[FieldOffset(1)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] error; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response. - public struct mavlink_param_ext_request_read_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=249)] + /// An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon. + public struct mavlink_open_drone_id_message_pack_t { /// packet ordered constructor - public mavlink_param_ext_request_read_t(short param_index,byte target_system,byte target_component,byte[] param_id) + public mavlink_open_drone_id_message_pack_t(byte target_system,byte target_component,byte[] id_or_mac,byte single_message_size,byte msg_pack_size,byte[] messages) { - this.param_index = param_index; this.target_system = target_system; this.target_component = target_component; - this.param_id = param_id; + this.id_or_mac = id_or_mac; + this.single_message_size = single_message_size; + this.msg_pack_size = msg_pack_size; + this.messages = messages; } /// packet xml order - public static mavlink_param_ext_request_read_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,short param_index) + public static mavlink_open_drone_id_message_pack_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,byte single_message_size,byte msg_pack_size,byte[] messages) { - var msg = new mavlink_param_ext_request_read_t(); + var msg = new mavlink_open_drone_id_message_pack_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.param_id = param_id; - msg.param_index = param_index; + msg.id_or_mac = id_or_mac; + msg.single_message_size = single_message_size; + msg.msg_pack_size = msg_pack_size; + msg.messages = messages; return msg; } - /// Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) + /// System ID (0 for broadcast). [Units("")] - [Description("Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)")] + [Description("System ID (0 for broadcast).")] //[FieldOffset(0)] - public short param_index; + public byte target_system; - /// System ID + /// Component ID (0 for broadcast). [Units("")] - [Description("System ID")] + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(1)] + public byte target_component; + + /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + [Units("")] + [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] //[FieldOffset(2)] - public byte target_system; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] + public byte[] id_or_mac; - /// Component ID + /// This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length. [bytes] + [Units("[bytes]")] + [Description("This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.")] + //[FieldOffset(22)] + public byte single_message_size; + + /// Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. [Units("")] - [Description("Component ID")] - //[FieldOffset(3)] - public byte target_component; + [Description("Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.")] + //[FieldOffset(23)] + public byte msg_pack_size; - /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. [Units("")] - [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [Description("Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=225)] + public byte[] messages; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - /// Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE. - public struct mavlink_param_ext_request_list_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] + /// Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location. + public struct mavlink_open_drone_id_system_update_t { /// packet ordered constructor - public mavlink_param_ext_request_list_t(byte target_system,byte target_component) + public mavlink_open_drone_id_system_update_t(int operator_latitude,int operator_longitude,float operator_altitude_geo,uint timestamp,byte target_system,byte target_component) { + this.operator_latitude = operator_latitude; + this.operator_longitude = operator_longitude; + this.operator_altitude_geo = operator_altitude_geo; + this.timestamp = timestamp; this.target_system = target_system; this.target_component = target_component; } /// packet xml order - public static mavlink_param_ext_request_list_t PopulateXMLOrder(byte target_system,byte target_component) + public static mavlink_open_drone_id_system_update_t PopulateXMLOrder(byte target_system,byte target_component,int operator_latitude,int operator_longitude,float operator_altitude_geo,uint timestamp) { - var msg = new mavlink_param_ext_request_list_t(); + var msg = new mavlink_open_drone_id_system_update_t(); msg.target_system = target_system; msg.target_component = target_component; + msg.operator_latitude = operator_latitude; + msg.operator_longitude = operator_longitude; + msg.operator_altitude_geo = operator_altitude_geo; + msg.timestamp = timestamp; return msg; } - /// System ID - [Units("")] - [Description("System ID")] + /// Latitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] + [Units("[degE7]")] + [Description("Latitude of the operator. If unknown: 0 (both Lat/Lon).")] //[FieldOffset(0)] + public int operator_latitude; + + /// Longitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] + [Units("[degE7]")] + [Description("Longitude of the operator. If unknown: 0 (both Lat/Lon).")] + //[FieldOffset(4)] + public int operator_longitude; + + /// Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. [m] + [Units("[m]")] + [Description("Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.")] + //[FieldOffset(8)] + public float operator_altitude_geo; + + /// 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. [s] + [Units("[s]")] + [Description("32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.")] + //[FieldOffset(12)] + public uint timestamp; + + /// System ID (0 for broadcast). + [Units("")] + [Description("System ID (0 for broadcast).")] + //[FieldOffset(16)] public byte target_system; - /// Component ID + /// Component ID (0 for broadcast). [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] + [Description("Component ID (0 for broadcast).")] + //[FieldOffset(17)] public byte target_component; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=149)] - /// Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout. - public struct mavlink_param_ext_value_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// Temperature and humidity from hygrometer. + public struct mavlink_hygrometer_sensor_t { /// packet ordered constructor - public mavlink_param_ext_value_t(ushort param_count,ushort param_index,byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type) + public mavlink_hygrometer_sensor_t(short temperature,ushort humidity,byte id) { - this.param_count = param_count; - this.param_index = param_index; - this.param_id = param_id; - this.param_value = param_value; - this.param_type = param_type; + this.temperature = temperature; + this.humidity = humidity; + this.id = id; } /// packet xml order - public static mavlink_param_ext_value_t PopulateXMLOrder(byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type,ushort param_count,ushort param_index) + public static mavlink_hygrometer_sensor_t PopulateXMLOrder(byte id,short temperature,ushort humidity) { - var msg = new mavlink_param_ext_value_t(); + var msg = new mavlink_hygrometer_sensor_t(); - msg.param_id = param_id; - msg.param_value = param_value; - msg.param_type = param_type; - msg.param_count = param_count; - msg.param_index = param_index; + msg.id = id; + msg.temperature = temperature; + msg.humidity = humidity; return msg; } - /// Total number of parameters - [Units("")] - [Description("Total number of parameters")] + /// Temperature [cdegC] + [Units("[cdegC]")] + [Description("Temperature")] //[FieldOffset(0)] - public ushort param_count; + public short temperature; - /// Index of this parameter - [Units("")] - [Description("Index of this parameter")] + /// Humidity [c%] + [Units("[c%]")] + [Description("Humidity")] //[FieldOffset(2)] - public ushort param_index; + public ushort humidity; - /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + /// Hygrometer ID [Units("")] - [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + [Description("Hygrometer ID")] //[FieldOffset(4)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; - - /// Parameter value - [Units("")] - [Description("Parameter value")] - //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] - public byte[] param_value; - - /// Parameter type. MAV_PARAM_EXT_TYPE - [Units("")] - [Description("Parameter type.")] - //[FieldOffset(148)] - public /*MAV_PARAM_EXT_TYPE*/byte param_type; + public byte id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=147)] - /// Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response. - public struct mavlink_param_ext_set_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] + /// Checksum for the current mission, rally point or geofence plan, or for the 'combined' plan (a GCS can use these checksums to determine if it has matching plans). This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition (immediately after the MISSION_ACK that completes the upload sequence). It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required. The checksum must be calculated on the autopilot, but may also be calculated by the GCS. The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation). The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order): frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7. The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point. + public struct mavlink_mission_checksum_t { /// packet ordered constructor - public mavlink_param_ext_set_t(byte target_system,byte target_component,byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type) + public mavlink_mission_checksum_t(uint checksum,/*MAV_MISSION_TYPE*/byte mission_type) { - this.target_system = target_system; - this.target_component = target_component; - this.param_id = param_id; - this.param_value = param_value; - this.param_type = param_type; + this.checksum = checksum; + this.mission_type = mission_type; } /// packet xml order - public static mavlink_param_ext_set_t PopulateXMLOrder(byte target_system,byte target_component,byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type) + public static mavlink_mission_checksum_t PopulateXMLOrder(/*MAV_MISSION_TYPE*/byte mission_type,uint checksum) { - var msg = new mavlink_param_ext_set_t(); + var msg = new mavlink_mission_checksum_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.param_id = param_id; - msg.param_value = param_value; - msg.param_type = param_type; + msg.mission_type = mission_type; + msg.checksum = checksum; return msg; } - /// System ID + /// CRC32 checksum of current plan for specified type. [Units("")] - [Description("System ID")] + [Description("CRC32 checksum of current plan for specified type.")] //[FieldOffset(0)] - public byte target_system; - - /// Component ID - [Units("")] - [Description("Component ID")] - //[FieldOffset(1)] - public byte target_component; - - /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - [Units("")] - [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; - - /// Parameter value - [Units("")] - [Description("Parameter value")] - //[FieldOffset(18)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] - public byte[] param_value; + public uint checksum; - /// Parameter type. MAV_PARAM_EXT_TYPE + /// Mission type. MAV_MISSION_TYPE [Units("")] - [Description("Parameter type.")] - //[FieldOffset(146)] - public /*MAV_PARAM_EXT_TYPE*/byte param_type; + [Description("Mission type.")] + //[FieldOffset(4)] + public /*MAV_MISSION_TYPE*/byte mission_type; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=146)] - /// Response from a PARAM_EXT_SET message. - public struct mavlink_param_ext_ack_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] + /// Airspeed information from a sensor. + public struct mavlink_airspeed_t { /// packet ordered constructor - public mavlink_param_ext_ack_t(byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type,/*PARAM_ACK*/byte param_result) + public mavlink_airspeed_t(float airspeed,float raw_press,short temperature,byte id,/*AIRSPEED_SENSOR_FLAGS*/byte flags) { - this.param_id = param_id; - this.param_value = param_value; - this.param_type = param_type; - this.param_result = param_result; + this.airspeed = airspeed; + this.raw_press = raw_press; + this.temperature = temperature; + this.id = id; + this.flags = flags; } /// packet xml order - public static mavlink_param_ext_ack_t PopulateXMLOrder(byte[] param_id,byte[] param_value,/*MAV_PARAM_EXT_TYPE*/byte param_type,/*PARAM_ACK*/byte param_result) + public static mavlink_airspeed_t PopulateXMLOrder(byte id,float airspeed,short temperature,float raw_press,/*AIRSPEED_SENSOR_FLAGS*/byte flags) { - var msg = new mavlink_param_ext_ack_t(); + var msg = new mavlink_airspeed_t(); - msg.param_id = param_id; - msg.param_value = param_value; - msg.param_type = param_type; - msg.param_result = param_result; + msg.id = id; + msg.airspeed = airspeed; + msg.temperature = temperature; + msg.raw_press = raw_press; + msg.flags = flags; return msg; } - /// Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - [Units("")] - [Description("Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string")] + /// Calibrated airspeed (CAS). [m/s] + [Units("[m/s]")] + [Description("Calibrated airspeed (CAS).")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + public float airspeed; - /// Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) - [Units("")] - [Description("Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] - public byte[] param_value; + /// Raw differential pressure. NaN for value unknown/not supplied. [hPa] + [Units("[hPa]")] + [Description("Raw differential pressure. NaN for value unknown/not supplied.")] + //[FieldOffset(4)] + public float raw_press; - /// Parameter type. MAV_PARAM_EXT_TYPE + /// Temperature. INT16_MAX for value unknown/not supplied. [cdegC] + [Units("[cdegC]")] + [Description("Temperature. INT16_MAX for value unknown/not supplied.")] + //[FieldOffset(8)] + public short temperature; + + /// Sensor ID. [Units("")] - [Description("Parameter type.")] - //[FieldOffset(144)] - public /*MAV_PARAM_EXT_TYPE*/byte param_type; + [Description("Sensor ID.")] + //[FieldOffset(10)] + public byte id; - /// Result code. PARAM_ACK + /// Airspeed sensor flags. AIRSPEED_SENSOR_FLAGS [Units("")] - [Description("Result code.")] - //[FieldOffset(145)] - public /*PARAM_ACK*/byte param_result; + [Description("Airspeed sensor flags.")] + //[FieldOffset(11)] + public /*AIRSPEED_SENSOR_FLAGS*/byte flags; }; - /// extensions_start 6 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=167)] - /// Obstacle distances in front of the sensor, starting from the left in increment degrees to the right - public struct mavlink_obstacle_distance_t + /// extensions_start 5 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=73)] + /// RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components (allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS). Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar messages reported by the flight controller. The target_system field should normally be set to the system id of the system to control, typically the flight controller. The target_component field can normally be set to 0, so that all components of the system can receive the message. The channels array field can publish up to 32 channels; the number of channel items used in the array is specified in the count field. The time_last_update_ms field contains the timestamp of the last received valid channels data in the receiver's time domain. The count field indicates the first index of the channel array that is not used for channel data (this and later indexes are zero-filled). The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be validated so the last valid data is resent). The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition is met (implementation dependent, e.g., connection to the RC radio is lost). In this case time_last_update_ms still contains the timestamp of the last valid channels data, but the content of the channels data is not defined by the protocol (it is up to the implementation of the receiver). For instance, the channels data could contain failsafe values configured in the receiver; the default is to carry the last valid data. Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload and subject to MAVLink's trailing-zero trimming. + public struct mavlink_radio_rc_channels_t { /// packet ordered constructor - public mavlink_obstacle_distance_t(ulong time_usec,ushort[] distances,ushort min_distance,ushort max_distance,/*MAV_DISTANCE_SENSOR*/byte sensor_type,byte increment,float increment_f,float angle_offset,/*MAV_FRAME*/byte frame) + public mavlink_radio_rc_channels_t(uint time_last_update_ms,/*RADIO_RC_CHANNELS_FLAGS*/ushort flags,byte target_system,byte target_component,byte count,short[] channels) { - this.time_usec = time_usec; - this.distances = distances; - this.min_distance = min_distance; - this.max_distance = max_distance; - this.sensor_type = sensor_type; - this.increment = increment; - this.increment_f = increment_f; - this.angle_offset = angle_offset; - this.frame = frame; + this.time_last_update_ms = time_last_update_ms; + this.flags = flags; + this.target_system = target_system; + this.target_component = target_component; + this.count = count; + this.channels = channels; } /// packet xml order - public static mavlink_obstacle_distance_t PopulateXMLOrder(ulong time_usec,/*MAV_DISTANCE_SENSOR*/byte sensor_type,ushort[] distances,byte increment,ushort min_distance,ushort max_distance,float increment_f,float angle_offset,/*MAV_FRAME*/byte frame) + public static mavlink_radio_rc_channels_t PopulateXMLOrder(byte target_system,byte target_component,uint time_last_update_ms,/*RADIO_RC_CHANNELS_FLAGS*/ushort flags,byte count,short[] channels) { - var msg = new mavlink_obstacle_distance_t(); + var msg = new mavlink_radio_rc_channels_t(); - msg.time_usec = time_usec; - msg.sensor_type = sensor_type; - msg.distances = distances; - msg.increment = increment; - msg.min_distance = min_distance; - msg.max_distance = max_distance; - msg.increment_f = increment_f; - msg.angle_offset = angle_offset; - msg.frame = frame; + msg.target_system = target_system; + msg.target_component = target_component; + msg.time_last_update_ms = time_last_update_ms; + msg.flags = flags; + msg.count = count; + msg.channels = channels; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Time when the data in the channels field were last updated (time since boot in the receiver's time domain). [ms] + [Units("[ms]")] + [Description("Time when the data in the channels field were last updated (time since boot in the receiver's time domain).")] //[FieldOffset(0)] - public ulong time_usec; - - /// Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. [cm] - [Units("[cm]")] - [Description("Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=72)] - public ushort[] distances; - - /// Minimum distance the sensor can measure. [cm] - [Units("[cm]")] - [Description("Minimum distance the sensor can measure.")] - //[FieldOffset(152)] - public ushort min_distance; - - /// Maximum distance the sensor can measure. [cm] - [Units("[cm]")] - [Description("Maximum distance the sensor can measure.")] - //[FieldOffset(154)] - public ushort max_distance; + public uint time_last_update_ms; - /// Class id of the distance sensor type. MAV_DISTANCE_SENSOR + /// Radio RC channels status flags. RADIO_RC_CHANNELS_FLAGS bitmask [Units("")] - [Description("Class id of the distance sensor type.")] - //[FieldOffset(156)] - public /*MAV_DISTANCE_SENSOR*/byte sensor_type; + [Description("Radio RC channels status flags.")] + //[FieldOffset(4)] + public /*RADIO_RC_CHANNELS_FLAGS*/ushort flags; - /// Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. [deg] - [Units("[deg]")] - [Description("Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.")] - //[FieldOffset(157)] - public byte increment; + /// System ID (ID of target system, normally flight controller). + [Units("")] + [Description("System ID (ID of target system, normally flight controller).")] + //[FieldOffset(6)] + public byte target_system; - /// Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. [deg] - [Units("[deg]")] - [Description("Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.")] - //[FieldOffset(158)] - public float increment_f; + /// Component ID (normally 0 for broadcast). + [Units("")] + [Description("Component ID (normally 0 for broadcast).")] + //[FieldOffset(7)] + public byte target_component; - /// Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. [deg] - [Units("[deg]")] - [Description("Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.")] - //[FieldOffset(162)] - public float angle_offset; + /// Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message. + [Units("")] + [Description("Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message.")] + //[FieldOffset(8)] + public byte count; - /// Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. MAV_FRAME + /// RC channels. Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500. Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming. [Units("")] - [Description("Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.")] - //[FieldOffset(166)] - public /*MAV_FRAME*/byte frame; + [Description("RC channels. Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500. Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.")] + //[FieldOffset(9)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public short[] channels; }; - /// extensions_start 15 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=233)] - /// Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html). - public struct mavlink_odometry_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] + /// Get information about a particular flight modes. The message can be enumerated or requested for a particular mode using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each modes should only be emitted once (even if it is both standard and custom). + public struct mavlink_available_modes_t { /// packet ordered constructor - public mavlink_odometry_t(ulong time_usec,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,sbyte quality) + public mavlink_available_modes_t(uint custom_mode,/*MAV_MODE_PROPERTY*/uint properties,byte number_modes,byte mode_index,/*MAV_STANDARD_MODE*/byte standard_mode,byte[] mode_name) { - this.time_usec = time_usec; - this.x = x; - this.y = y; - this.z = z; - this.q = q; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.rollspeed = rollspeed; - this.pitchspeed = pitchspeed; - this.yawspeed = yawspeed; - this.pose_covariance = pose_covariance; - this.velocity_covariance = velocity_covariance; - this.frame_id = frame_id; - this.child_frame_id = child_frame_id; - this.reset_counter = reset_counter; - this.estimator_type = estimator_type; - this.quality = quality; + this.custom_mode = custom_mode; + this.properties = properties; + this.number_modes = number_modes; + this.mode_index = mode_index; + this.standard_mode = standard_mode; + this.mode_name = mode_name; } /// packet xml order - public static mavlink_odometry_t PopulateXMLOrder(ulong time_usec,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,sbyte quality) + public static mavlink_available_modes_t PopulateXMLOrder(byte number_modes,byte mode_index,/*MAV_STANDARD_MODE*/byte standard_mode,uint custom_mode,/*MAV_MODE_PROPERTY*/uint properties,byte[] mode_name) { - var msg = new mavlink_odometry_t(); + var msg = new mavlink_available_modes_t(); - msg.time_usec = time_usec; - msg.frame_id = frame_id; - msg.child_frame_id = child_frame_id; - msg.x = x; - msg.y = y; - msg.z = z; - msg.q = q; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.rollspeed = rollspeed; - msg.pitchspeed = pitchspeed; - msg.yawspeed = yawspeed; - msg.pose_covariance = pose_covariance; - msg.velocity_covariance = velocity_covariance; - msg.reset_counter = reset_counter; - msg.estimator_type = estimator_type; - msg.quality = quality; + msg.number_modes = number_modes; + msg.mode_index = mode_index; + msg.standard_mode = standard_mode; + msg.custom_mode = custom_mode; + msg.properties = properties; + msg.mode_name = mode_name; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// A bitfield for use for autopilot-specific flags + [Units("")] + [Description("A bitfield for use for autopilot-specific flags")] //[FieldOffset(0)] - public ulong time_usec; - - /// X Position [m] - [Units("[m]")] - [Description("X Position")] - //[FieldOffset(8)] - public float x; - - /// Y Position [m] - [Units("[m]")] - [Description("Y Position")] - //[FieldOffset(12)] - public float y; - - /// Z Position [m] - [Units("[m]")] - [Description("Z Position")] - //[FieldOffset(16)] - public float z; + public uint custom_mode; - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + /// Mode properties. MAV_MODE_PROPERTY [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)")] - //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; + [Description("Mode properties.")] + //[FieldOffset(4)] + public /*MAV_MODE_PROPERTY*/uint properties; - /// X linear speed [m/s] - [Units("[m/s]")] - [Description("X linear speed")] - //[FieldOffset(36)] - public float vx; + /// The total number of available modes for the current vehicle type. + [Units("")] + [Description("The total number of available modes for the current vehicle type.")] + //[FieldOffset(8)] + public byte number_modes; - /// Y linear speed [m/s] - [Units("[m/s]")] - [Description("Y linear speed")] - //[FieldOffset(40)] - public float vy; + /// The current mode index within number_modes, indexed from 1. + [Units("")] + [Description("The current mode index within number_modes, indexed from 1.")] + //[FieldOffset(9)] + public byte mode_index; - /// Z linear speed [m/s] - [Units("[m/s]")] - [Description("Z linear speed")] - //[FieldOffset(44)] - public float vz; + /// Standard mode. MAV_STANDARD_MODE + [Units("")] + [Description("Standard mode.")] + //[FieldOffset(10)] + public /*MAV_STANDARD_MODE*/byte standard_mode; - /// Roll angular speed [rad/s] - [Units("[rad/s]")] - [Description("Roll angular speed")] - //[FieldOffset(48)] - public float rollspeed; + /// Name of custom mode, with null termination character. Should be omitted for standard modes. + [Units("")] + [Description("Name of custom mode, with null termination character. Should be omitted for standard modes.")] + //[FieldOffset(11)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=35)] + public byte[] mode_name; + }; - /// Pitch angular speed [rad/s] - [Units("[rad/s]")] - [Description("Pitch angular speed")] - //[FieldOffset(52)] - public float pitchspeed; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. + public struct mavlink_current_mode_t + { + /// packet ordered constructor + public mavlink_current_mode_t(uint custom_mode,uint intended_custom_mode,/*MAV_STANDARD_MODE*/byte standard_mode) + { + this.custom_mode = custom_mode; + this.intended_custom_mode = intended_custom_mode; + this.standard_mode = standard_mode; + + } + + /// packet xml order + public static mavlink_current_mode_t PopulateXMLOrder(/*MAV_STANDARD_MODE*/byte standard_mode,uint custom_mode,uint intended_custom_mode) + { + var msg = new mavlink_current_mode_t(); - /// Yaw angular speed [rad/s] - [Units("[rad/s]")] - [Description("Yaw angular speed")] - //[FieldOffset(56)] - public float yawspeed; + msg.standard_mode = standard_mode; + msg.custom_mode = custom_mode; + msg.intended_custom_mode = intended_custom_mode; + + return msg; + } + - /// Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. + /// A bitfield for use for autopilot-specific flags [Units("")] - [Description("Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(60)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] - public float[] pose_covariance; + [Description("A bitfield for use for autopilot-specific flags")] + //[FieldOffset(0)] + public uint custom_mode; - /// Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. + /// The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied [Units("")] - [Description("Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.")] - //[FieldOffset(144)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=21)] - public float[] velocity_covariance; + [Description("The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied")] + //[FieldOffset(4)] + public uint intended_custom_mode; - /// Coordinate frame of reference for the pose data. MAV_FRAME + /// Standard mode. MAV_STANDARD_MODE [Units("")] - [Description("Coordinate frame of reference for the pose data.")] - //[FieldOffset(228)] - public /*MAV_FRAME*/byte frame_id; + [Description("Standard mode.")] + //[FieldOffset(8)] + public /*MAV_STANDARD_MODE*/byte standard_mode; + }; - /// Coordinate frame of reference for the velocity in free space (twist) data. MAV_FRAME - [Units("")] - [Description("Coordinate frame of reference for the velocity in free space (twist) data.")] - //[FieldOffset(229)] - public /*MAV_FRAME*/byte child_frame_id; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] + /// A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. + public struct mavlink_available_modes_monitor_t + { + /// packet ordered constructor + public mavlink_available_modes_monitor_t(byte seq) + { + this.seq = seq; + + } + + /// packet xml order + public static mavlink_available_modes_monitor_t PopulateXMLOrder(byte seq) + { + var msg = new mavlink_available_modes_monitor_t(); - /// Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - [Units("")] - [Description("Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.")] - //[FieldOffset(230)] - public byte reset_counter; + msg.seq = seq; + + return msg; + } + - /// Type of estimator that is providing the odometry. MAV_ESTIMATOR_TYPE + /// Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically). [Units("")] - [Description("Type of estimator that is providing the odometry.")] - //[FieldOffset(231)] - public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; - - /// Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality [%] - [Units("[%]")] - [Description("Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality")] - //[FieldOffset(232)] - public sbyte quality; + [Description("Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically).")] + //[FieldOffset(0)] + public byte seq; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] - /// Status of the Iridium SBD link. - public struct mavlink_isbd_link_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] + /// Information about key components of GNSS receivers, like signal authentication, interference and system errors. + public struct mavlink_gnss_integrity_t { /// packet ordered constructor - public mavlink_isbd_link_status_t(ulong timestamp,ulong last_heartbeat,ushort failed_sessions,ushort successful_sessions,byte signal_quality,byte ring_pending,byte tx_session_pending,byte rx_session_pending) + public mavlink_gnss_integrity_t(/*GPS_SYSTEM_ERROR_FLAGS*/uint system_errors,ushort raim_hfom,ushort raim_vfom,byte id,/*GPS_AUTHENTICATION_STATE*/byte authentication_state,/*GPS_JAMMING_STATE*/byte jamming_state,/*GPS_SPOOFING_STATE*/byte spoofing_state,/*GPS_RAIM_STATE*/byte raim_state,byte corrections_quality,byte system_status_summary,byte gnss_signal_quality,byte post_processing_quality) { - this.timestamp = timestamp; - this.last_heartbeat = last_heartbeat; - this.failed_sessions = failed_sessions; - this.successful_sessions = successful_sessions; - this.signal_quality = signal_quality; - this.ring_pending = ring_pending; - this.tx_session_pending = tx_session_pending; - this.rx_session_pending = rx_session_pending; + this.system_errors = system_errors; + this.raim_hfom = raim_hfom; + this.raim_vfom = raim_vfom; + this.id = id; + this.authentication_state = authentication_state; + this.jamming_state = jamming_state; + this.spoofing_state = spoofing_state; + this.raim_state = raim_state; + this.corrections_quality = corrections_quality; + this.system_status_summary = system_status_summary; + this.gnss_signal_quality = gnss_signal_quality; + this.post_processing_quality = post_processing_quality; } /// packet xml order - public static mavlink_isbd_link_status_t PopulateXMLOrder(ulong timestamp,ulong last_heartbeat,ushort failed_sessions,ushort successful_sessions,byte signal_quality,byte ring_pending,byte tx_session_pending,byte rx_session_pending) + public static mavlink_gnss_integrity_t PopulateXMLOrder(byte id,/*GPS_SYSTEM_ERROR_FLAGS*/uint system_errors,/*GPS_AUTHENTICATION_STATE*/byte authentication_state,/*GPS_JAMMING_STATE*/byte jamming_state,/*GPS_SPOOFING_STATE*/byte spoofing_state,/*GPS_RAIM_STATE*/byte raim_state,ushort raim_hfom,ushort raim_vfom,byte corrections_quality,byte system_status_summary,byte gnss_signal_quality,byte post_processing_quality) { - var msg = new mavlink_isbd_link_status_t(); + var msg = new mavlink_gnss_integrity_t(); - msg.timestamp = timestamp; - msg.last_heartbeat = last_heartbeat; - msg.failed_sessions = failed_sessions; - msg.successful_sessions = successful_sessions; - msg.signal_quality = signal_quality; - msg.ring_pending = ring_pending; - msg.tx_session_pending = tx_session_pending; - msg.rx_session_pending = rx_session_pending; + msg.id = id; + msg.system_errors = system_errors; + msg.authentication_state = authentication_state; + msg.jamming_state = jamming_state; + msg.spoofing_state = spoofing_state; + msg.raim_state = raim_state; + msg.raim_hfom = raim_hfom; + msg.raim_vfom = raim_vfom; + msg.corrections_quality = corrections_quality; + msg.system_status_summary = system_status_summary; + msg.gnss_signal_quality = gnss_signal_quality; + msg.post_processing_quality = post_processing_quality; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// Errors in the GPS system. GPS_SYSTEM_ERROR_FLAGS bitmask + [Units("")] + [Description("Errors in the GPS system.")] //[FieldOffset(0)] - public ulong timestamp; + public /*GPS_SYSTEM_ERROR_FLAGS*/uint system_errors; - /// Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. [us] - [Units("[us]")] - [Description("Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.")] + /// Horizontal expected accuracy using satellites successfully validated using RAIM. [cm] + [Units("[cm]")] + [Description("Horizontal expected accuracy using satellites successfully validated using RAIM.")] + //[FieldOffset(4)] + public ushort raim_hfom; + + /// Vertical expected accuracy using satellites successfully validated using RAIM. [cm] + [Units("[cm]")] + [Description("Vertical expected accuracy using satellites successfully validated using RAIM.")] + //[FieldOffset(6)] + public ushort raim_vfom; + + /// GNSS receiver id. Must match instance ids of other messages from same receiver. + [Units("")] + [Description("GNSS receiver id. Must match instance ids of other messages from same receiver.")] //[FieldOffset(8)] - public ulong last_heartbeat; + public byte id; - /// Number of failed SBD sessions. + /// Signal authentication state of the GPS system. GPS_AUTHENTICATION_STATE [Units("")] - [Description("Number of failed SBD sessions.")] - //[FieldOffset(16)] - public ushort failed_sessions; + [Description("Signal authentication state of the GPS system.")] + //[FieldOffset(9)] + public /*GPS_AUTHENTICATION_STATE*/byte authentication_state; - /// Number of successful SBD sessions. + /// Signal jamming state of the GPS system. GPS_JAMMING_STATE [Units("")] - [Description("Number of successful SBD sessions.")] - //[FieldOffset(18)] - public ushort successful_sessions; + [Description("Signal jamming state of the GPS system.")] + //[FieldOffset(10)] + public /*GPS_JAMMING_STATE*/byte jamming_state; - /// Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. + /// Signal spoofing state of the GPS system. GPS_SPOOFING_STATE [Units("")] - [Description("Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.")] - //[FieldOffset(20)] - public byte signal_quality; + [Description("Signal spoofing state of the GPS system.")] + //[FieldOffset(11)] + public /*GPS_SPOOFING_STATE*/byte spoofing_state; - /// 1: Ring call pending, 0: No call pending. + /// The state of the RAIM processing. GPS_RAIM_STATE [Units("")] - [Description("1: Ring call pending, 0: No call pending.")] - //[FieldOffset(21)] - public byte ring_pending; + [Description("The state of the RAIM processing.")] + //[FieldOffset(12)] + public /*GPS_RAIM_STATE*/byte raim_state; - /// 1: Transmission session pending, 0: No transmission session pending. + /// An abstract value representing the estimated quality of incoming corrections, or 255 if not available. [Units("")] - [Description("1: Transmission session pending, 0: No transmission session pending.")] - //[FieldOffset(22)] - public byte tx_session_pending; + [Description("An abstract value representing the estimated quality of incoming corrections, or 255 if not available.")] + //[FieldOffset(13)] + public byte corrections_quality; - /// 1: Receiving session pending, 0: No receiving session pending. + /// An abstract value representing the overall status of the receiver, or 255 if not available. [Units("")] - [Description("1: Receiving session pending, 0: No receiving session pending.")] - //[FieldOffset(23)] - public byte rx_session_pending; + [Description("An abstract value representing the overall status of the receiver, or 255 if not available.")] + //[FieldOffset(14)] + public byte system_status_summary; + + /// An abstract value representing the quality of incoming GNSS signals, or 255 if not available. + [Units("")] + [Description("An abstract value representing the quality of incoming GNSS signals, or 255 if not available.")] + //[FieldOffset(15)] + public byte gnss_signal_quality; + + /// An abstract value representing the estimated PPK quality, or 255 if not available. + [Units("")] + [Description("An abstract value representing the estimated PPK quality, or 255 if not available.")] + //[FieldOffset(16)] + public byte post_processing_quality; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// RPM sensor data message. - public struct mavlink_raw_rpm_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] + /// ICAROUS heartbeat + public struct mavlink_icarous_heartbeat_t { /// packet ordered constructor - public mavlink_raw_rpm_t(float frequency,byte index) + public mavlink_icarous_heartbeat_t(/*ICAROUS_FMS_STATE*/byte status) { - this.frequency = frequency; - this.index = index; + this.status = status; } /// packet xml order - public static mavlink_raw_rpm_t PopulateXMLOrder(byte index,float frequency) + public static mavlink_icarous_heartbeat_t PopulateXMLOrder(/*ICAROUS_FMS_STATE*/byte status) { - var msg = new mavlink_raw_rpm_t(); + var msg = new mavlink_icarous_heartbeat_t(); - msg.index = index; - msg.frequency = frequency; + msg.status = status; return msg; } - /// Indicated rate [rpm] - [Units("[rpm]")] - [Description("Indicated rate")] - //[FieldOffset(0)] - public float frequency; - - /// Index of this RPM sensor (0-indexed) + /// See the FMS_STATE enum. ICAROUS_FMS_STATE [Units("")] - [Description("Index of this RPM sensor (0-indexed)")] - //[FieldOffset(4)] - public byte index; + [Description("See the FMS_STATE enum.")] + //[FieldOffset(0)] + public /*ICAROUS_FMS_STATE*/byte status; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=70)] - /// The global position resulting from GPS and sensor fusion. - public struct mavlink_utm_global_position_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] + /// Kinematic multi bands (track) output from Daidalus + public struct mavlink_icarous_kinematic_bands_t { /// packet ordered constructor - public mavlink_utm_global_position_t(ulong time,int lat,int lon,int alt,int relative_alt,int next_lat,int next_lon,int next_alt,short vx,short vy,short vz,ushort h_acc,ushort v_acc,ushort vel_acc,ushort update_rate,byte[] uas_id,/*UTM_FLIGHT_STATE*/byte flight_state,/*UTM_DATA_AVAIL_FLAGS*/byte flags) + public mavlink_icarous_kinematic_bands_t(float min1,float max1,float min2,float max2,float min3,float max3,float min4,float max4,float min5,float max5,sbyte numBands,/*ICAROUS_TRACK_BAND_TYPES*/byte type1,/*ICAROUS_TRACK_BAND_TYPES*/byte type2,/*ICAROUS_TRACK_BAND_TYPES*/byte type3,/*ICAROUS_TRACK_BAND_TYPES*/byte type4,/*ICAROUS_TRACK_BAND_TYPES*/byte type5) { - this.time = time; - this.lat = lat; - this.lon = lon; - this.alt = alt; - this.relative_alt = relative_alt; - this.next_lat = next_lat; - this.next_lon = next_lon; - this.next_alt = next_alt; - this.vx = vx; - this.vy = vy; - this.vz = vz; - this.h_acc = h_acc; - this.v_acc = v_acc; - this.vel_acc = vel_acc; - this.update_rate = update_rate; - this.uas_id = uas_id; - this.flight_state = flight_state; - this.flags = flags; + this.min1 = min1; + this.max1 = max1; + this.min2 = min2; + this.max2 = max2; + this.min3 = min3; + this.max3 = max3; + this.min4 = min4; + this.max4 = max4; + this.min5 = min5; + this.max5 = max5; + this.numBands = numBands; + this.type1 = type1; + this.type2 = type2; + this.type3 = type3; + this.type4 = type4; + this.type5 = type5; } /// packet xml order - public static mavlink_utm_global_position_t PopulateXMLOrder(ulong time,byte[] uas_id,int lat,int lon,int alt,int relative_alt,short vx,short vy,short vz,ushort h_acc,ushort v_acc,ushort vel_acc,int next_lat,int next_lon,int next_alt,ushort update_rate,/*UTM_FLIGHT_STATE*/byte flight_state,/*UTM_DATA_AVAIL_FLAGS*/byte flags) + public static mavlink_icarous_kinematic_bands_t PopulateXMLOrder(sbyte numBands,/*ICAROUS_TRACK_BAND_TYPES*/byte type1,float min1,float max1,/*ICAROUS_TRACK_BAND_TYPES*/byte type2,float min2,float max2,/*ICAROUS_TRACK_BAND_TYPES*/byte type3,float min3,float max3,/*ICAROUS_TRACK_BAND_TYPES*/byte type4,float min4,float max4,/*ICAROUS_TRACK_BAND_TYPES*/byte type5,float min5,float max5) { - var msg = new mavlink_utm_global_position_t(); + var msg = new mavlink_icarous_kinematic_bands_t(); - msg.time = time; - msg.uas_id = uas_id; - msg.lat = lat; - msg.lon = lon; - msg.alt = alt; - msg.relative_alt = relative_alt; - msg.vx = vx; - msg.vy = vy; - msg.vz = vz; - msg.h_acc = h_acc; - msg.v_acc = v_acc; - msg.vel_acc = vel_acc; - msg.next_lat = next_lat; - msg.next_lon = next_lon; - msg.next_alt = next_alt; - msg.update_rate = update_rate; - msg.flight_state = flight_state; - msg.flags = flags; + msg.numBands = numBands; + msg.type1 = type1; + msg.min1 = min1; + msg.max1 = max1; + msg.type2 = type2; + msg.min2 = min2; + msg.max2 = max2; + msg.type3 = type3; + msg.min3 = min3; + msg.max3 = max3; + msg.type4 = type4; + msg.min4 = min4; + msg.max4 = max4; + msg.type5 = type5; + msg.min5 = min5; + msg.max5 = max5; return msg; } - /// Time of applicability of position (microseconds since UNIX epoch). [us] - [Units("[us]")] - [Description("Time of applicability of position (microseconds since UNIX epoch).")] + /// min angle (degrees) [deg] + [Units("[deg]")] + [Description("min angle (degrees)")] //[FieldOffset(0)] - public ulong time; + public float min1; - /// Latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Latitude (WGS84)")] + /// max angle (degrees) [deg] + [Units("[deg]")] + [Description("max angle (degrees)")] + //[FieldOffset(4)] + public float max1; + + /// min angle (degrees) [deg] + [Units("[deg]")] + [Description("min angle (degrees)")] //[FieldOffset(8)] - public int lat; + public float min2; - /// Longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Longitude (WGS84)")] + /// max angle (degrees) [deg] + [Units("[deg]")] + [Description("max angle (degrees)")] //[FieldOffset(12)] - public int lon; + public float max2; - /// Altitude (WGS84) [mm] - [Units("[mm]")] - [Description("Altitude (WGS84)")] + /// min angle (degrees) [deg] + [Units("[deg]")] + [Description("min angle (degrees)")] //[FieldOffset(16)] - public int alt; + public float min3; - /// Altitude above ground [mm] - [Units("[mm]")] - [Description("Altitude above ground")] + /// max angle (degrees) [deg] + [Units("[deg]")] + [Description("max angle (degrees)")] //[FieldOffset(20)] - public int relative_alt; + public float max3; - /// Next waypoint, latitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Next waypoint, latitude (WGS84)")] + /// min angle (degrees) [deg] + [Units("[deg]")] + [Description("min angle (degrees)")] //[FieldOffset(24)] - public int next_lat; + public float min4; - /// Next waypoint, longitude (WGS84) [degE7] - [Units("[degE7]")] - [Description("Next waypoint, longitude (WGS84)")] + /// max angle (degrees) [deg] + [Units("[deg]")] + [Description("max angle (degrees)")] //[FieldOffset(28)] - public int next_lon; + public float max4; - /// Next waypoint, altitude (WGS84) [mm] - [Units("[mm]")] - [Description("Next waypoint, altitude (WGS84)")] + /// min angle (degrees) [deg] + [Units("[deg]")] + [Description("min angle (degrees)")] //[FieldOffset(32)] - public int next_alt; + public float min5; - /// Ground X speed (latitude, positive north) [cm/s] - [Units("[cm/s]")] - [Description("Ground X speed (latitude, positive north)")] + /// max angle (degrees) [deg] + [Units("[deg]")] + [Description("max angle (degrees)")] //[FieldOffset(36)] - public short vx; - - /// Ground Y speed (longitude, positive east) [cm/s] - [Units("[cm/s]")] - [Description("Ground Y speed (longitude, positive east)")] - //[FieldOffset(38)] - public short vy; - - /// Ground Z speed (altitude, positive down) [cm/s] - [Units("[cm/s]")] - [Description("Ground Z speed (altitude, positive down)")] - //[FieldOffset(40)] - public short vz; - - /// Horizontal position uncertainty (standard deviation) [mm] - [Units("[mm]")] - [Description("Horizontal position uncertainty (standard deviation)")] - //[FieldOffset(42)] - public ushort h_acc; + public float max5; - /// Altitude uncertainty (standard deviation) [mm] - [Units("[mm]")] - [Description("Altitude uncertainty (standard deviation)")] - //[FieldOffset(44)] - public ushort v_acc; + /// Number of track bands + [Units("")] + [Description("Number of track bands")] + //[FieldOffset(40)] + public sbyte numBands; - /// Speed uncertainty (standard deviation) [cm/s] - [Units("[cm/s]")] - [Description("Speed uncertainty (standard deviation)")] - //[FieldOffset(46)] - public ushort vel_acc; + /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES + [Units("")] + [Description("See the TRACK_BAND_TYPES enum.")] + //[FieldOffset(41)] + public /*ICAROUS_TRACK_BAND_TYPES*/byte type1; - /// Time until next update. Set to 0 if unknown or in data driven mode. [cs] - [Units("[cs]")] - [Description("Time until next update. Set to 0 if unknown or in data driven mode.")] - //[FieldOffset(48)] - public ushort update_rate; + /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES + [Units("")] + [Description("See the TRACK_BAND_TYPES enum.")] + //[FieldOffset(42)] + public /*ICAROUS_TRACK_BAND_TYPES*/byte type2; - /// Unique UAS ID. + /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES [Units("")] - [Description("Unique UAS ID.")] - //[FieldOffset(50)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=18)] - public byte[] uas_id; + [Description("See the TRACK_BAND_TYPES enum.")] + //[FieldOffset(43)] + public /*ICAROUS_TRACK_BAND_TYPES*/byte type3; - /// Flight state UTM_FLIGHT_STATE + /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES [Units("")] - [Description("Flight state")] - //[FieldOffset(68)] - public /*UTM_FLIGHT_STATE*/byte flight_state; + [Description("See the TRACK_BAND_TYPES enum.")] + //[FieldOffset(44)] + public /*ICAROUS_TRACK_BAND_TYPES*/byte type4; - /// Bitwise OR combination of the data available flags. UTM_DATA_AVAIL_FLAGS bitmask + /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES [Units("")] - [Description("Bitwise OR combination of the data available flags.")] - //[FieldOffset(69)] - public /*UTM_DATA_AVAIL_FLAGS*/byte flags; + [Description("See the TRACK_BAND_TYPES enum.")] + //[FieldOffset(45)] + public /*ICAROUS_TRACK_BAND_TYPES*/byte type5; }; - /// extensions_start 3 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=252)] - /// Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code. - public struct mavlink_debug_float_array_t + /// 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 + public struct mavlink_heartbeat_t { /// packet ordered constructor - public mavlink_debug_float_array_t(ulong time_usec,ushort array_id,byte[] name,float[] data) + public mavlink_heartbeat_t(uint custom_mode,/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,/*MAV_MODE_FLAG*/byte base_mode,/*MAV_STATE*/byte system_status,byte mavlink_version) { - this.time_usec = time_usec; - this.array_id = array_id; - this.name = name; - this.data = data; + this.custom_mode = custom_mode; + this.type = type; + this.autopilot = autopilot; + this.base_mode = base_mode; + this.system_status = system_status; + this.mavlink_version = mavlink_version; } /// packet xml order - public static mavlink_debug_float_array_t PopulateXMLOrder(ulong time_usec,byte[] name,ushort array_id,float[] data) + public static mavlink_heartbeat_t PopulateXMLOrder(/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,/*MAV_MODE_FLAG*/byte base_mode,uint custom_mode,/*MAV_STATE*/byte system_status,byte mavlink_version) { - var msg = new mavlink_debug_float_array_t(); + var msg = new mavlink_heartbeat_t(); - msg.time_usec = time_usec; - msg.name = name; - msg.array_id = array_id; - msg.data = data; + msg.type = type; + msg.autopilot = autopilot; + msg.base_mode = base_mode; + msg.custom_mode = custom_mode; + msg.system_status = system_status; + msg.mavlink_version = mavlink_version; return msg; } - /// 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. [us] - [Units("[us]")] - [Description("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.")] + /// A bitfield for use for autopilot-specific flags + [Units("")] + [Description("A bitfield for use for autopilot-specific flags")] //[FieldOffset(0)] - public ulong time_usec; + public uint custom_mode; - /// Unique ID used to discriminate between arrays + /// Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. MAV_TYPE [Units("")] - [Description("Unique ID used to discriminate between arrays")] - //[FieldOffset(8)] - public ushort array_id; + [Description("Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.")] + //[FieldOffset(4)] + public /*MAV_TYPE*/byte type; - /// Name, for human-friendly display in a Ground Control Station + /// Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. MAV_AUTOPILOT [Units("")] - [Description("Name, for human-friendly display in a Ground Control Station")] - //[FieldOffset(10)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; + [Description("Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.")] + //[FieldOffset(5)] + public /*MAV_AUTOPILOT*/byte autopilot; - /// data + /// System mode bitmap. MAV_MODE_FLAG bitmask [Units("")] - [Description("data")] - //[FieldOffset(20)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=58)] - public float[] data; + [Description("System mode bitmap.")] + //[FieldOffset(6)] + public /*MAV_MODE_FLAG*/byte base_mode; + + /// System status flag. MAV_STATE + [Units("")] + [Description("System status flag.")] + //[FieldOffset(7)] + public /*MAV_STATE*/byte system_status; + + /// MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + [Units("")] + [Description("MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version")] + //[FieldOffset(8)] + public byte mavlink_version; }; - /// extensions_start 12 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=109)] - /// Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for smart battery frequent updates. - public struct mavlink_smart_battery_info_t + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// Array test #0. + public struct mavlink_array_test_0_t { /// packet ordered constructor - public mavlink_smart_battery_info_t(int capacity_full_specification,int capacity_full,ushort cycle_count,ushort weight,ushort discharge_minimum_voltage,ushort charging_minimum_voltage,ushort resting_minimum_voltage,byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,byte[] serial_number,byte[] device_name,ushort charging_maximum_voltage,byte cells_in_series,uint discharge_maximum_current,uint discharge_maximum_burst_current,byte[] manufacture_date) + public mavlink_array_test_0_t(uint[] ar_u32,ushort[] ar_u16,byte v1,sbyte[] ar_i8,byte[] ar_u8) { - this.capacity_full_specification = capacity_full_specification; - this.capacity_full = capacity_full; - this.cycle_count = cycle_count; - this.weight = weight; - this.discharge_minimum_voltage = discharge_minimum_voltage; - this.charging_minimum_voltage = charging_minimum_voltage; - this.resting_minimum_voltage = resting_minimum_voltage; - this.id = id; - this.battery_function = battery_function; - this.type = type; - this.serial_number = serial_number; - this.device_name = device_name; - this.charging_maximum_voltage = charging_maximum_voltage; - this.cells_in_series = cells_in_series; - this.discharge_maximum_current = discharge_maximum_current; - this.discharge_maximum_burst_current = discharge_maximum_burst_current; - this.manufacture_date = manufacture_date; + this.ar_u32 = ar_u32; + this.ar_u16 = ar_u16; + this.v1 = v1; + this.ar_i8 = ar_i8; + this.ar_u8 = ar_u8; } /// packet xml order - public static mavlink_smart_battery_info_t PopulateXMLOrder(byte id,/*MAV_BATTERY_FUNCTION*/byte battery_function,/*MAV_BATTERY_TYPE*/byte type,int capacity_full_specification,int capacity_full,ushort cycle_count,byte[] serial_number,byte[] device_name,ushort weight,ushort discharge_minimum_voltage,ushort charging_minimum_voltage,ushort resting_minimum_voltage,ushort charging_maximum_voltage,byte cells_in_series,uint discharge_maximum_current,uint discharge_maximum_burst_current,byte[] manufacture_date) + public static mavlink_array_test_0_t PopulateXMLOrder(byte v1,sbyte[] ar_i8,byte[] ar_u8,ushort[] ar_u16,uint[] ar_u32) { - var msg = new mavlink_smart_battery_info_t(); + var msg = new mavlink_array_test_0_t(); - msg.id = id; - msg.battery_function = battery_function; - msg.type = type; - msg.capacity_full_specification = capacity_full_specification; - msg.capacity_full = capacity_full; - msg.cycle_count = cycle_count; - msg.serial_number = serial_number; - msg.device_name = device_name; - msg.weight = weight; - msg.discharge_minimum_voltage = discharge_minimum_voltage; - msg.charging_minimum_voltage = charging_minimum_voltage; - msg.resting_minimum_voltage = resting_minimum_voltage; - msg.charging_maximum_voltage = charging_maximum_voltage; - msg.cells_in_series = cells_in_series; - msg.discharge_maximum_current = discharge_maximum_current; - msg.discharge_maximum_burst_current = discharge_maximum_burst_current; - msg.manufacture_date = manufacture_date; + msg.v1 = v1; + msg.ar_i8 = ar_i8; + msg.ar_u8 = ar_u8; + msg.ar_u16 = ar_u16; + msg.ar_u32 = ar_u32; return msg; } - /// Capacity when full according to manufacturer, -1: field not provided. [mAh] - [Units("[mAh]")] - [Description("Capacity when full according to manufacturer, -1: field not provided.")] + /// Value array + [Units("")] + [Description("Value array")] //[FieldOffset(0)] - public int capacity_full_specification; - - /// Capacity when full (accounting for battery degradation), -1: field not provided. [mAh] - [Units("[mAh]")] - [Description("Capacity when full (accounting for battery degradation), -1: field not provided.")] - //[FieldOffset(4)] - public int capacity_full; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public uint[] ar_u32; - /// Charge/discharge cycle count. UINT16_MAX: field not provided. + /// Value array [Units("")] - [Description("Charge/discharge cycle count. UINT16_MAX: field not provided.")] - //[FieldOffset(8)] - public ushort cycle_count; - - /// Battery weight. 0: field not provided. [g] - [Units("[g]")] - [Description("Battery weight. 0: field not provided.")] - //[FieldOffset(10)] - public ushort weight; - - /// Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. [mV] - [Units("[mV]")] - [Description("Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value.")] - //[FieldOffset(12)] - public ushort discharge_minimum_voltage; - - /// Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. [mV] - [Units("[mV]")] - [Description("Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value.")] - //[FieldOffset(14)] - public ushort charging_minimum_voltage; - - /// Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. [mV] - [Units("[mV]")] - [Description("Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value.")] + [Description("Value array")] //[FieldOffset(16)] - public ushort resting_minimum_voltage; - - /// Battery ID - [Units("")] - [Description("Battery ID")] - //[FieldOffset(18)] - public byte id; - - /// Function of the battery MAV_BATTERY_FUNCTION - [Units("")] - [Description("Function of the battery")] - //[FieldOffset(19)] - public /*MAV_BATTERY_FUNCTION*/byte battery_function; - - /// Type (chemistry) of the battery MAV_BATTERY_TYPE - [Units("")] - [Description("Type (chemistry) of the battery")] - //[FieldOffset(20)] - public /*MAV_BATTERY_TYPE*/byte type; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public ushort[] ar_u16; - /// Serial number in ASCII characters, 0 terminated. All 0: field not provided. + /// Stub field [Units("")] - [Description("Serial number in ASCII characters, 0 terminated. All 0: field not provided.")] - //[FieldOffset(21)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] serial_number; + [Description("Stub field")] + //[FieldOffset(24)] + public byte v1; - /// Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. + /// Value array [Units("")] - [Description("Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore.")] - //[FieldOffset(37)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] - public byte[] device_name; - - /// Maximum per-cell voltage when charged. 0: field not provided. [mV] - [Units("[mV]")] - [Description("Maximum per-cell voltage when charged. 0: field not provided.")] - //[FieldOffset(87)] - public ushort charging_maximum_voltage; + [Description("Value array")] + //[FieldOffset(25)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public sbyte[] ar_i8; - /// Number of battery cells in series. 0: field not provided. + /// Value array [Units("")] - [Description("Number of battery cells in series. 0: field not provided.")] - //[FieldOffset(89)] - public byte cells_in_series; + [Description("Value array")] + //[FieldOffset(29)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public byte[] ar_u8; + }; - /// Maximum pack discharge current. 0: field not provided. [mA] - [Units("[mA]")] - [Description("Maximum pack discharge current. 0: field not provided.")] - //[FieldOffset(90)] - public uint discharge_maximum_current; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] + /// Array test #1. + public struct mavlink_array_test_1_t + { + /// packet ordered constructor + public mavlink_array_test_1_t(uint[] ar_u32) + { + this.ar_u32 = ar_u32; + + } + + /// packet xml order + public static mavlink_array_test_1_t PopulateXMLOrder(uint[] ar_u32) + { + var msg = new mavlink_array_test_1_t(); - /// Maximum pack discharge burst current. 0: field not provided. [mA] - [Units("[mA]")] - [Description("Maximum pack discharge burst current. 0: field not provided.")] - //[FieldOffset(94)] - public uint discharge_maximum_burst_current; + msg.ar_u32 = ar_u32; + + return msg; + } + - /// Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. + /// Value array [Units("")] - [Description("Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided.")] - //[FieldOffset(98)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=11)] - public byte[] manufacture_date; + [Description("Value array")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public uint[] ar_u32; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - /// Telemetry of power generation system. Alternator or mechanical generator. - public struct mavlink_generator_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] + /// Array test #3. + public struct mavlink_array_test_3_t { /// packet ordered constructor - public mavlink_generator_status_t(/*MAV_GENERATOR_STATUS_FLAG*/ulong status,float battery_current,float load_current,float power_generated,float bus_voltage,float bat_current_setpoint,uint runtime,int time_until_maintenance,ushort generator_speed,short rectifier_temperature,short generator_temperature) + public mavlink_array_test_3_t(uint[] ar_u32,byte v) { - this.status = status; - this.battery_current = battery_current; - this.load_current = load_current; - this.power_generated = power_generated; - this.bus_voltage = bus_voltage; - this.bat_current_setpoint = bat_current_setpoint; - this.runtime = runtime; - this.time_until_maintenance = time_until_maintenance; - this.generator_speed = generator_speed; - this.rectifier_temperature = rectifier_temperature; - this.generator_temperature = generator_temperature; + this.ar_u32 = ar_u32; + this.v = v; } /// packet xml order - public static mavlink_generator_status_t PopulateXMLOrder(/*MAV_GENERATOR_STATUS_FLAG*/ulong status,ushort generator_speed,float battery_current,float load_current,float power_generated,float bus_voltage,short rectifier_temperature,float bat_current_setpoint,short generator_temperature,uint runtime,int time_until_maintenance) + public static mavlink_array_test_3_t PopulateXMLOrder(byte v,uint[] ar_u32) { - var msg = new mavlink_generator_status_t(); + var msg = new mavlink_array_test_3_t(); - msg.status = status; - msg.generator_speed = generator_speed; - msg.battery_current = battery_current; - msg.load_current = load_current; - msg.power_generated = power_generated; - msg.bus_voltage = bus_voltage; - msg.rectifier_temperature = rectifier_temperature; - msg.bat_current_setpoint = bat_current_setpoint; - msg.generator_temperature = generator_temperature; - msg.runtime = runtime; - msg.time_until_maintenance = time_until_maintenance; + msg.v = v; + msg.ar_u32 = ar_u32; return msg; } - /// Status flags. MAV_GENERATOR_STATUS_FLAG bitmask + /// Value array [Units("")] - [Description("Status flags.")] + [Description("Value array")] //[FieldOffset(0)] - public /*MAV_GENERATOR_STATUS_FLAG*/ulong status; - - /// Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. [A] - [Units("[A]")] - [Description("Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.")] - //[FieldOffset(8)] - public float battery_current; - - /// Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided [A] - [Units("[A]")] - [Description("Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided")] - //[FieldOffset(12)] - public float load_current; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public uint[] ar_u32; - /// The power being generated. NaN: field not provided [W] - [Units("[W]")] - [Description("The power being generated. NaN: field not provided")] + /// Stub field + [Units("")] + [Description("Stub field")] //[FieldOffset(16)] - public float power_generated; - - /// Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. [V] - [Units("[V]")] - [Description("Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.")] - //[FieldOffset(20)] - public float bus_voltage; - - /// The target battery current. Positive for out. Negative for in. NaN: field not provided [A] - [Units("[A]")] - [Description("The target battery current. Positive for out. Negative for in. NaN: field not provided")] - //[FieldOffset(24)] - public float bat_current_setpoint; - - /// Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. [s] - [Units("[s]")] - [Description("Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.")] - //[FieldOffset(28)] - public uint runtime; + public byte v; + }; - /// Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. [s] - [Units("[s]")] - [Description("Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.")] - //[FieldOffset(32)] - public int time_until_maintenance; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] + /// Array test #4. + public struct mavlink_array_test_4_t + { + /// packet ordered constructor + public mavlink_array_test_4_t(uint[] ar_u32,byte v) + { + this.ar_u32 = ar_u32; + this.v = v; + + } + + /// packet xml order + public static mavlink_array_test_4_t PopulateXMLOrder(uint[] ar_u32,byte v) + { + var msg = new mavlink_array_test_4_t(); - /// Speed of electrical generator or alternator. UINT16_MAX: field not provided. [rpm] - [Units("[rpm]")] - [Description("Speed of electrical generator or alternator. UINT16_MAX: field not provided.")] - //[FieldOffset(36)] - public ushort generator_speed; + msg.ar_u32 = ar_u32; + msg.v = v; + + return msg; + } + - /// The temperature of the rectifier or power converter. INT16_MAX: field not provided. [degC] - [Units("[degC]")] - [Description("The temperature of the rectifier or power converter. INT16_MAX: field not provided.")] - //[FieldOffset(38)] - public short rectifier_temperature; + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public uint[] ar_u32; - /// The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. [degC] - [Units("[degC]")] - [Description("The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.")] - //[FieldOffset(40)] - public short generator_temperature; + /// Stub field + [Units("")] + [Description("Stub field")] + //[FieldOffset(16)] + public byte v; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=140)] - /// The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW. - public struct mavlink_actuator_output_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=10)] + /// Array test #5. + public struct mavlink_array_test_5_t { /// packet ordered constructor - public mavlink_actuator_output_status_t(ulong time_usec,uint active,float[] actuator) + public mavlink_array_test_5_t(byte[] c1,byte[] c2) { - this.time_usec = time_usec; - this.active = active; - this.actuator = actuator; + this.c1 = c1; + this.c2 = c2; } /// packet xml order - public static mavlink_actuator_output_status_t PopulateXMLOrder(ulong time_usec,uint active,float[] actuator) + public static mavlink_array_test_5_t PopulateXMLOrder(byte[] c1,byte[] c2) { - var msg = new mavlink_actuator_output_status_t(); + var msg = new mavlink_array_test_5_t(); - msg.time_usec = time_usec; - msg.active = active; - msg.actuator = actuator; + msg.c1 = c1; + msg.c2 = c2; return msg; } - /// Timestamp (since system boot). [us] - [Units("[us]")] - [Description("Timestamp (since system boot).")] - //[FieldOffset(0)] - public ulong time_usec; - - /// Active outputs bitmask + /// Value array [Units("")] - [Description("Active outputs")] - //[FieldOffset(8)] - public uint active; + [Description("Value array")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public byte[] c1; - /// Servo / motor output array values. Zero values indicate unused channels. + /// Value array [Units("")] - [Description("Servo / motor output array values. Zero values indicate unused channels.")] - //[FieldOffset(12)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public float[] actuator; + [Description("Value array")] + //[FieldOffset(5)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public byte[] c2; }; /// 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 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=91)] + /// Array test #6. + public struct mavlink_array_test_6_t { /// packet ordered constructor - public mavlink_relay_status_t(uint time_boot_ms,ushort on,ushort present) + public mavlink_array_test_6_t(double[] ar_d,uint v3,uint[] ar_u32,int[] ar_i32,float[] ar_f,ushort v2,ushort[] ar_u16,short[] ar_i16,byte v1,byte[] ar_u8,sbyte[] ar_i8,byte[] ar_c) { - this.time_boot_ms = time_boot_ms; - this.on = on; - this.present = present; + this.ar_d = ar_d; + this.v3 = v3; + this.ar_u32 = ar_u32; + this.ar_i32 = ar_i32; + this.ar_f = ar_f; + this.v2 = v2; + this.ar_u16 = ar_u16; + this.ar_i16 = ar_i16; + this.v1 = v1; + this.ar_u8 = ar_u8; + this.ar_i8 = ar_i8; + this.ar_c = ar_c; } /// packet xml order - public static mavlink_relay_status_t PopulateXMLOrder(uint time_boot_ms,ushort on,ushort present) + public static mavlink_array_test_6_t PopulateXMLOrder(byte v1,ushort v2,uint v3,uint[] ar_u32,int[] ar_i32,ushort[] ar_u16,short[] ar_i16,byte[] ar_u8,sbyte[] ar_i8,byte[] ar_c,double[] ar_d,float[] ar_f) { - var msg = new mavlink_relay_status_t(); + var msg = new mavlink_array_test_6_t(); - msg.time_boot_ms = time_boot_ms; - msg.on = on; - msg.present = present; + msg.v1 = v1; + msg.v2 = v2; + msg.v3 = v3; + msg.ar_u32 = ar_u32; + msg.ar_i32 = ar_i32; + msg.ar_u16 = ar_u16; + msg.ar_i16 = ar_i16; + msg.ar_u8 = ar_u8; + msg.ar_i8 = ar_i8; + msg.ar_c = ar_c; + msg.ar_d = ar_d; + msg.ar_f = ar_f; return msg; } - /// Timestamp (time since system boot). [ms] - [Units("[ms]")] - [Description("Timestamp (time since system boot).")] + /// Value array + [Units("")] + [Description("Value array")] //[FieldOffset(0)] - public uint time_boot_ms; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public double[] ar_d; - /// Relay states. Relay instance numbers are represented as individual bits in this mask by offset. bitmask + /// Stub field [Units("")] - [Description("Relay states. Relay instance numbers are represented as individual bits in this mask by offset.")] - //[FieldOffset(4)] - public ushort on; + [Description("Stub field")] + //[FieldOffset(16)] + public uint v3; - /// 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 + /// Value array [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; + [Description("Value array")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public uint[] ar_u32; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(28)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public int[] ar_i32; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(36)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public float[] ar_f; + + /// Stub field + [Units("")] + [Description("Stub field")] + //[FieldOffset(44)] + public ushort v2; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(46)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public ushort[] ar_u16; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(50)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public short[] ar_i16; + + /// Stub field + [Units("")] + [Description("Stub field")] + //[FieldOffset(54)] + public byte v1; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(55)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public byte[] ar_u8; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(57)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public sbyte[] ar_i8; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(59)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] ar_c; }; /// 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. - public struct mavlink_tunnel_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=84)] + /// Array test #7. + public struct mavlink_array_test_7_t { /// packet ordered constructor - public mavlink_tunnel_t(/*MAV_TUNNEL_PAYLOAD_TYPE*/ushort payload_type,byte target_system,byte target_component,byte payload_length,byte[] payload) + public mavlink_array_test_7_t(double[] ar_d,float[] ar_f,uint[] ar_u32,int[] ar_i32,ushort[] ar_u16,short[] ar_i16,byte[] ar_u8,sbyte[] ar_i8,byte[] ar_c) { - this.payload_type = payload_type; - this.target_system = target_system; - this.target_component = target_component; - this.payload_length = payload_length; - this.payload = payload; + this.ar_d = ar_d; + this.ar_f = ar_f; + this.ar_u32 = ar_u32; + this.ar_i32 = ar_i32; + this.ar_u16 = ar_u16; + this.ar_i16 = ar_i16; + this.ar_u8 = ar_u8; + this.ar_i8 = ar_i8; + this.ar_c = ar_c; } /// packet xml order - public static mavlink_tunnel_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_TUNNEL_PAYLOAD_TYPE*/ushort payload_type,byte payload_length,byte[] payload) + public static mavlink_array_test_7_t PopulateXMLOrder(double[] ar_d,float[] ar_f,uint[] ar_u32,int[] ar_i32,ushort[] ar_u16,short[] ar_i16,byte[] ar_u8,sbyte[] ar_i8,byte[] ar_c) { - var msg = new mavlink_tunnel_t(); + var msg = new mavlink_array_test_7_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.payload_type = payload_type; - msg.payload_length = payload_length; - msg.payload = payload; + msg.ar_d = ar_d; + msg.ar_f = ar_f; + msg.ar_u32 = ar_u32; + msg.ar_i32 = ar_i32; + msg.ar_u16 = ar_u16; + msg.ar_i16 = ar_i16; + msg.ar_u8 = ar_u8; + msg.ar_i8 = ar_i8; + msg.ar_c = ar_c; return msg; } - /// A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. MAV_TUNNEL_PAYLOAD_TYPE + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public double[] ar_d; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public float[] ar_f; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public uint[] ar_u32; + + /// Value array [Units("")] - [Description("A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.")] - //[FieldOffset(0)] - public /*MAV_TUNNEL_PAYLOAD_TYPE*/ushort payload_type; + [Description("Value array")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public int[] ar_i32; - /// System ID (can be 0 for broadcast, but this is discouraged) + /// Value array [Units("")] - [Description("System ID (can be 0 for broadcast, but this is discouraged)")] - //[FieldOffset(2)] - public byte target_system; + [Description("Value array")] + //[FieldOffset(40)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public ushort[] ar_u16; - /// Component ID (can be 0 for broadcast, but this is discouraged) + /// Value array [Units("")] - [Description("Component ID (can be 0 for broadcast, but this is discouraged)")] - //[FieldOffset(3)] - public byte target_component; + [Description("Value array")] + //[FieldOffset(44)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public short[] ar_i16; - /// Length of the data transported in payload + /// Value array [Units("")] - [Description("Length of the data transported in payload")] - //[FieldOffset(4)] - public byte payload_length; + [Description("Value array")] + //[FieldOffset(48)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public byte[] ar_u8; - /// Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. + /// Value array [Units("")] - [Description("Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type.")] - //[FieldOffset(5)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=128)] - public byte[] payload; + [Description("Value array")] + //[FieldOffset(50)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public sbyte[] ar_i8; + + /// Value array + [Units("")] + [Description("Value array")] + //[FieldOffset(52)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] + public byte[] ar_c; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - /// A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD. - public struct mavlink_can_frame_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// Array test #8. + public struct mavlink_array_test_8_t { /// packet ordered constructor - public mavlink_can_frame_t(uint id,byte target_system,byte target_component,byte bus,byte len,byte[] data) + public mavlink_array_test_8_t(double[] ar_d,uint v3,ushort[] ar_u16) { - this.id = id; - this.target_system = target_system; - this.target_component = target_component; - this.bus = bus; - this.len = len; - this.data = data; + this.ar_d = ar_d; + this.v3 = v3; + this.ar_u16 = ar_u16; } /// packet xml order - public static mavlink_can_frame_t PopulateXMLOrder(byte target_system,byte target_component,byte bus,byte len,uint id,byte[] data) + public static mavlink_array_test_8_t PopulateXMLOrder(uint v3,double[] ar_d,ushort[] ar_u16) { - var msg = new mavlink_can_frame_t(); + var msg = new mavlink_array_test_8_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.bus = bus; - msg.len = len; - msg.id = id; - msg.data = data; + msg.v3 = v3; + msg.ar_d = ar_d; + msg.ar_u16 = ar_u16; return msg; } - /// Frame ID + /// Value array [Units("")] - [Description("Frame ID")] + [Description("Value array")] //[FieldOffset(0)] - public uint id; - - /// System ID. - [Units("")] - [Description("System ID.")] - //[FieldOffset(4)] - public byte target_system; - - /// Component ID. - [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; - - /// bus number - [Units("")] - [Description("bus number")] - //[FieldOffset(6)] - public byte bus; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public double[] ar_d; - /// Frame length + /// Stub field [Units("")] - [Description("Frame length")] - //[FieldOffset(7)] - public byte len; + [Description("Stub field")] + //[FieldOffset(16)] + public uint v3; - /// Frame data + /// Value array [Units("")] - [Description("Frame data")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public byte[] data; + [Description("Value array")] + //[FieldOffset(20)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public ushort[] ar_u16; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=72)] - /// A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling) - public struct mavlink_canfd_frame_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=179)] + /// Test all field types + public struct mavlink_test_types_t { /// packet ordered constructor - public mavlink_canfd_frame_t(uint id,byte target_system,byte target_component,byte bus,byte len,byte[] data) + public mavlink_test_types_t(ulong u64,long s64,double d,ulong[] u64_array,long[] s64_array,double[] d_array,uint u32,int s32,float f,uint[] u32_array,int[] s32_array,float[] f_array,ushort u16,short s16,ushort[] u16_array,short[] s16_array,byte c,byte[] s,byte u8,sbyte s8,byte[] u8_array,sbyte[] s8_array) { - this.id = id; - this.target_system = target_system; - this.target_component = target_component; - this.bus = bus; - this.len = len; - this.data = data; + this.u64 = u64; + this.s64 = s64; + this.d = d; + this.u64_array = u64_array; + this.s64_array = s64_array; + this.d_array = d_array; + this.u32 = u32; + this.s32 = s32; + this.f = f; + this.u32_array = u32_array; + this.s32_array = s32_array; + this.f_array = f_array; + this.u16 = u16; + this.s16 = s16; + this.u16_array = u16_array; + this.s16_array = s16_array; + this.c = c; + this.s = s; + this.u8 = u8; + this.s8 = s8; + this.u8_array = u8_array; + this.s8_array = s8_array; } /// packet xml order - public static mavlink_canfd_frame_t PopulateXMLOrder(byte target_system,byte target_component,byte bus,byte len,uint id,byte[] data) + public static mavlink_test_types_t PopulateXMLOrder(byte c,byte[] s,byte u8,ushort u16,uint u32,ulong u64,sbyte s8,short s16,int s32,long s64,float f,double d,byte[] u8_array,ushort[] u16_array,uint[] u32_array,ulong[] u64_array,sbyte[] s8_array,short[] s16_array,int[] s32_array,long[] s64_array,float[] f_array,double[] d_array) { - var msg = new mavlink_canfd_frame_t(); + var msg = new mavlink_test_types_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.bus = bus; - msg.len = len; - msg.id = id; - msg.data = data; + msg.c = c; + msg.s = s; + msg.u8 = u8; + msg.u16 = u16; + msg.u32 = u32; + msg.u64 = u64; + msg.s8 = s8; + msg.s16 = s16; + msg.s32 = s32; + msg.s64 = s64; + msg.f = f; + msg.d = d; + msg.u8_array = u8_array; + msg.u16_array = u16_array; + msg.u32_array = u32_array; + msg.u64_array = u64_array; + msg.s8_array = s8_array; + msg.s16_array = s16_array; + msg.s32_array = s32_array; + msg.s64_array = s64_array; + msg.f_array = f_array; + msg.d_array = d_array; return msg; } - /// Frame ID + /// uint64_t [Units("")] - [Description("Frame ID")] + [Description("uint64_t")] //[FieldOffset(0)] - public uint id; + public ulong u64; - /// System ID. + /// int64_t [Units("")] - [Description("System ID.")] - //[FieldOffset(4)] - public byte target_system; + [Description("int64_t")] + //[FieldOffset(8)] + public long s64; - /// Component ID. + /// double [Units("")] - [Description("Component ID.")] - //[FieldOffset(5)] - public byte target_component; + [Description("double")] + //[FieldOffset(16)] + public double d; - /// bus number + /// uint64_t_array [Units("")] - [Description("bus number")] - //[FieldOffset(6)] - public byte bus; + [Description("uint64_t_array")] + //[FieldOffset(24)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public ulong[] u64_array; - /// Frame length + /// int64_t_array [Units("")] - [Description("Frame length")] - //[FieldOffset(7)] - public byte len; + [Description("int64_t_array")] + //[FieldOffset(48)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public long[] s64_array; - /// Frame data + /// double_array [Units("")] - [Description("Frame data")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=64)] - public byte[] data; + [Description("double_array")] + //[FieldOffset(72)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public double[] d_array; + + /// uint32_t + [Units("")] + [Description("uint32_t")] + //[FieldOffset(96)] + public uint u32; + + /// int32_t + [Units("")] + [Description("int32_t")] + //[FieldOffset(100)] + public int s32; + + /// float + [Units("")] + [Description("float")] + //[FieldOffset(104)] + public float f; + + /// uint32_t_array + [Units("")] + [Description("uint32_t_array")] + //[FieldOffset(108)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public uint[] u32_array; + + /// int32_t_array + [Units("")] + [Description("int32_t_array")] + //[FieldOffset(120)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public int[] s32_array; + + /// float_array + [Units("")] + [Description("float_array")] + //[FieldOffset(132)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public float[] f_array; + + /// uint16_t + [Units("")] + [Description("uint16_t")] + //[FieldOffset(144)] + public ushort u16; + + /// int16_t + [Units("")] + [Description("int16_t")] + //[FieldOffset(146)] + public short s16; + + /// uint16_t_array + [Units("")] + [Description("uint16_t_array")] + //[FieldOffset(148)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public ushort[] u16_array; + + /// int16_t_array + [Units("")] + [Description("int16_t_array")] + //[FieldOffset(154)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public short[] s16_array; + + /// char + [Units("")] + [Description("char")] + //[FieldOffset(160)] + public byte c; + + /// string + [Units("")] + [Description("string")] + //[FieldOffset(161)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] + public byte[] s; + + /// uint8_t + [Units("")] + [Description("uint8_t")] + //[FieldOffset(171)] + public byte u8; + + /// int8_t + [Units("")] + [Description("int8_t")] + //[FieldOffset(172)] + public sbyte s8; + + /// uint8_t_array + [Units("")] + [Description("uint8_t_array")] + //[FieldOffset(173)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public byte[] u8_array; + + /// int8_t_array + [Units("")] + [Description("int8_t_array")] + //[FieldOffset(176)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public sbyte[] s8_array; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - /// Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwith links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages. - public struct mavlink_can_filter_modify_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] + /// Accelerometer and Gyro biases from the navigation filter + public struct mavlink_nav_filter_bias_t { /// packet ordered constructor - public mavlink_can_filter_modify_t(ushort[] ids,byte target_system,byte target_component,byte bus,/*CAN_FILTER_OP*/byte operation,byte num_ids) + public mavlink_nav_filter_bias_t(ulong usec,float accel_0,float accel_1,float accel_2,float gyro_0,float gyro_1,float gyro_2) { - this.ids = ids; - this.target_system = target_system; - this.target_component = target_component; - this.bus = bus; - this.operation = operation; - this.num_ids = num_ids; + this.usec = usec; + this.accel_0 = accel_0; + this.accel_1 = accel_1; + this.accel_2 = accel_2; + this.gyro_0 = gyro_0; + this.gyro_1 = gyro_1; + this.gyro_2 = gyro_2; } /// packet xml order - public static mavlink_can_filter_modify_t PopulateXMLOrder(byte target_system,byte target_component,byte bus,/*CAN_FILTER_OP*/byte operation,byte num_ids,ushort[] ids) + public static mavlink_nav_filter_bias_t PopulateXMLOrder(ulong usec,float accel_0,float accel_1,float accel_2,float gyro_0,float gyro_1,float gyro_2) { - var msg = new mavlink_can_filter_modify_t(); + var msg = new mavlink_nav_filter_bias_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.bus = bus; - msg.operation = operation; - msg.num_ids = num_ids; - msg.ids = ids; + msg.usec = usec; + msg.accel_0 = accel_0; + msg.accel_1 = accel_1; + msg.accel_2 = accel_2; + msg.gyro_0 = gyro_0; + msg.gyro_1 = gyro_1; + msg.gyro_2 = gyro_2; return msg; } - /// filter IDs, length num_ids + /// Timestamp (microseconds) [Units("")] - [Description("filter IDs, length num_ids")] + [Description("Timestamp (microseconds)")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public ushort[] ids; + public ulong usec; - /// System ID. + /// b_f[0] [Units("")] - [Description("System ID.")] - //[FieldOffset(32)] - public byte target_system; + [Description("b_f[0]")] + //[FieldOffset(8)] + public float accel_0; - /// Component ID. + /// b_f[1] [Units("")] - [Description("Component ID.")] - //[FieldOffset(33)] - public byte target_component; + [Description("b_f[1]")] + //[FieldOffset(12)] + public float accel_1; - /// bus number + /// b_f[2] [Units("")] - [Description("bus number")] - //[FieldOffset(34)] - public byte bus; + [Description("b_f[2]")] + //[FieldOffset(16)] + public float accel_2; - /// what operation to perform on the filter list. See CAN_FILTER_OP enum. CAN_FILTER_OP + /// b_f[0] [Units("")] - [Description("what operation to perform on the filter list. See CAN_FILTER_OP enum.")] - //[FieldOffset(35)] - public /*CAN_FILTER_OP*/byte operation; + [Description("b_f[0]")] + //[FieldOffset(20)] + public float gyro_0; - /// number of IDs in filter list + /// b_f[1] [Units("")] - [Description("number of IDs in filter list")] - //[FieldOffset(36)] - public byte num_ids; + [Description("b_f[1]")] + //[FieldOffset(24)] + public float gyro_1; + + /// b_f[2] + [Units("")] + [Description("b_f[2]")] + //[FieldOffset(28)] + public float gyro_2; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=137)] - /// Cumulative distance traveled for each reported wheel. - public struct mavlink_wheel_distance_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Complete set of calibration parameters for the radio + public struct mavlink_radio_calibration_t { /// packet ordered constructor - public mavlink_wheel_distance_t(ulong time_usec,double[] distance,byte count) + public mavlink_radio_calibration_t(ushort[] aileron,ushort[] elevator,ushort[] rudder,ushort[] gyro,ushort[] pitch,ushort[] throttle) { - this.time_usec = time_usec; - this.distance = distance; - this.count = count; + this.aileron = aileron; + this.elevator = elevator; + this.rudder = rudder; + this.gyro = gyro; + this.pitch = pitch; + this.throttle = throttle; } /// packet xml order - public static mavlink_wheel_distance_t PopulateXMLOrder(ulong time_usec,byte count,double[] distance) + public static mavlink_radio_calibration_t PopulateXMLOrder(ushort[] aileron,ushort[] elevator,ushort[] rudder,ushort[] gyro,ushort[] pitch,ushort[] throttle) { - var msg = new mavlink_wheel_distance_t(); + var msg = new mavlink_radio_calibration_t(); - msg.time_usec = time_usec; - msg.count = count; - msg.distance = distance; + msg.aileron = aileron; + msg.elevator = elevator; + msg.rudder = rudder; + msg.gyro = gyro; + msg.pitch = pitch; + msg.throttle = throttle; return msg; } - /// Timestamp (synced to UNIX time or since system boot). [us] - [Units("[us]")] - [Description("Timestamp (synced to UNIX time or since system boot).")] + /// Aileron setpoints: left, center, right + [Units("")] + [Description("Aileron setpoints: left, center, right")] //[FieldOffset(0)] - public ulong time_usec; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public ushort[] aileron; - /// Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. [m] - [Units("[m]")] - [Description("Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public double[] distance; + /// Elevator setpoints: nose down, center, nose up + [Units("")] + [Description("Elevator setpoints: nose down, center, nose up")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public ushort[] elevator; - /// Number of wheels reported. + /// Rudder setpoints: nose left, center, nose right [Units("")] - [Description("Number of wheels reported.")] - //[FieldOffset(136)] - public byte count; + [Description("Rudder setpoints: nose left, center, nose right")] + //[FieldOffset(12)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=3)] + public ushort[] rudder; + + /// Tail gyro mode/gain setpoints: heading hold, rate mode + [Units("")] + [Description("Tail gyro mode/gain setpoints: heading hold, rate mode")] + //[FieldOffset(18)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=2)] + public ushort[] gyro; + + /// Pitch curve setpoints (every 25%) + [Units("")] + [Description("Pitch curve setpoints (every 25%)")] + //[FieldOffset(22)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public ushort[] pitch; + + /// Throttle curve setpoints (every 25%) + [Units("")] + [Description("Throttle curve setpoints (every 25%)")] + //[FieldOffset(32)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=5)] + public ushort[] throttle; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] - /// Winch status. - public struct mavlink_winch_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] + /// System status specific to ualberta uav + public struct mavlink_ualberta_sys_status_t { /// packet ordered constructor - public mavlink_winch_status_t(ulong time_usec,float line_length,float speed,float tension,float voltage,float current,/*MAV_WINCH_STATUS_FLAG*/uint status,short temperature) + public mavlink_ualberta_sys_status_t(byte mode,byte nav_mode,byte pilot) { - this.time_usec = time_usec; - this.line_length = line_length; - this.speed = speed; - this.tension = tension; - this.voltage = voltage; - this.current = current; - this.status = status; - this.temperature = temperature; + this.mode = mode; + this.nav_mode = nav_mode; + this.pilot = pilot; } /// packet xml order - public static mavlink_winch_status_t PopulateXMLOrder(ulong time_usec,float line_length,float speed,float tension,float voltage,float current,short temperature,/*MAV_WINCH_STATUS_FLAG*/uint status) + public static mavlink_ualberta_sys_status_t PopulateXMLOrder(byte mode,byte nav_mode,byte pilot) { - var msg = new mavlink_winch_status_t(); + var msg = new mavlink_ualberta_sys_status_t(); - msg.time_usec = time_usec; - msg.line_length = line_length; - msg.speed = speed; - msg.tension = tension; - msg.voltage = voltage; - msg.current = current; - msg.temperature = temperature; - msg.status = status; + msg.mode = mode; + msg.nav_mode = nav_mode; + msg.pilot = pilot; return msg; } - /// Timestamp (synced to UNIX time or since system boot). [us] - [Units("[us]")] - [Description("Timestamp (synced to UNIX time or since system boot).")] + /// System mode, see UALBERTA_AUTOPILOT_MODE ENUM + [Units("")] + [Description("System mode, see UALBERTA_AUTOPILOT_MODE ENUM")] //[FieldOffset(0)] - public ulong time_usec; - - /// Length of line released. NaN if unknown [m] - [Units("[m]")] - [Description("Length of line released. NaN if unknown")] - //[FieldOffset(8)] - public float line_length; - - /// Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown [m/s] - [Units("[m/s]")] - [Description("Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown")] - //[FieldOffset(12)] - public float speed; - - /// Tension on the line. NaN if unknown [kg] - [Units("[kg]")] - [Description("Tension on the line. NaN if unknown")] - //[FieldOffset(16)] - public float tension; - - /// Voltage of the battery supplying the winch. NaN if unknown [V] - [Units("[V]")] - [Description("Voltage of the battery supplying the winch. NaN if unknown")] - //[FieldOffset(20)] - public float voltage; - - /// Current draw from the winch. NaN if unknown [A] - [Units("[A]")] - [Description("Current draw from the winch. NaN if unknown")] - //[FieldOffset(24)] - public float current; + public byte mode; - /// Status flags MAV_WINCH_STATUS_FLAG bitmask + /// Navigation mode, see UALBERTA_NAV_MODE ENUM [Units("")] - [Description("Status flags")] - //[FieldOffset(28)] - public /*MAV_WINCH_STATUS_FLAG*/uint status; + [Description("Navigation mode, see UALBERTA_NAV_MODE ENUM")] + //[FieldOffset(1)] + public byte nav_mode; - /// Temperature of the motor. INT16_MAX if unknown [degC] - [Units("[degC]")] - [Description("Temperature of the motor. INT16_MAX if unknown")] - //[FieldOffset(32)] - public short temperature; + /// Pilot mode, see UALBERTA_PILOT_MODE + [Units("")] + [Description("Pilot mode, see UALBERTA_PILOT_MODE")] + //[FieldOffset(2)] + public byte pilot; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - /// Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html. - public struct mavlink_open_drone_id_basic_id_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] + /// Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter) + public struct mavlink_uavionix_adsb_out_cfg_t { /// packet ordered constructor - public mavlink_open_drone_id_basic_id_t(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_ID_TYPE*/byte id_type,/*MAV_ODID_UA_TYPE*/byte ua_type,byte[] uas_id) + public mavlink_uavionix_adsb_out_cfg_t(uint ICAO,ushort stallSpeed,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitterType,/*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE*/byte aircraftSize,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT*/byte gpsOffsetLat,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON*/byte gpsOffsetLon,/*UAVIONIX_ADSB_OUT_RF_SELECT*/byte rfSelect) { - this.target_system = target_system; - this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.id_type = id_type; - this.ua_type = ua_type; - this.uas_id = uas_id; + this.ICAO = ICAO; + this.stallSpeed = stallSpeed; + this.callsign = callsign; + this.emitterType = emitterType; + this.aircraftSize = aircraftSize; + this.gpsOffsetLat = gpsOffsetLat; + this.gpsOffsetLon = gpsOffsetLon; + this.rfSelect = rfSelect; } /// packet xml order - public static mavlink_open_drone_id_basic_id_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_ID_TYPE*/byte id_type,/*MAV_ODID_UA_TYPE*/byte ua_type,byte[] uas_id) + public static mavlink_uavionix_adsb_out_cfg_t PopulateXMLOrder(uint ICAO,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitterType,/*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE*/byte aircraftSize,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT*/byte gpsOffsetLat,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON*/byte gpsOffsetLon,ushort stallSpeed,/*UAVIONIX_ADSB_OUT_RF_SELECT*/byte rfSelect) { - var msg = new mavlink_open_drone_id_basic_id_t(); + var msg = new mavlink_uavionix_adsb_out_cfg_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.id_type = id_type; - msg.ua_type = ua_type; - msg.uas_id = uas_id; + msg.ICAO = ICAO; + msg.callsign = callsign; + msg.emitterType = emitterType; + msg.aircraftSize = aircraftSize; + msg.gpsOffsetLat = gpsOffsetLat; + msg.gpsOffsetLon = gpsOffsetLon; + msg.stallSpeed = stallSpeed; + msg.rfSelect = rfSelect; return msg; } - /// System ID (0 for broadcast). + /// Vehicle address (24 bit) [Units("")] - [Description("System ID (0 for broadcast).")] + [Description("Vehicle address (24 bit)")] //[FieldOffset(0)] - public byte target_system; + public uint ICAO; - /// Component ID (0 for broadcast). + /// Aircraft stall speed in cm/s [cm/s] + [Units("[cm/s]")] + [Description("Aircraft stall speed in cm/s")] + //[FieldOffset(4)] + public ushort stallSpeed; + + /// Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, ' ' only) [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(1)] - public byte target_component; + [Description("Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, ' ' only)")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] + public byte[] callsign; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + /// Transmitting vehicle type. See ADSB_EMITTER_TYPE enum ADSB_EMITTER_TYPE [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; + [Description("Transmitting vehicle type. See ADSB_EMITTER_TYPE enum")] + //[FieldOffset(15)] + public /*ADSB_EMITTER_TYPE*/byte emitterType; - /// Indicates the format for the uas_id field of this message. MAV_ODID_ID_TYPE + /// Aircraft length and width encoding (table 2-35 of DO-282B) UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE [Units("")] - [Description("Indicates the format for the uas_id field of this message.")] - //[FieldOffset(22)] - public /*MAV_ODID_ID_TYPE*/byte id_type; + [Description("Aircraft length and width encoding (table 2-35 of DO-282B)")] + //[FieldOffset(16)] + public /*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE*/byte aircraftSize; - /// Indicates the type of UA (Unmanned Aircraft). MAV_ODID_UA_TYPE + /// GPS antenna lateral offset (table 2-36 of DO-282B) UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT [Units("")] - [Description("Indicates the type of UA (Unmanned Aircraft).")] - //[FieldOffset(23)] - public /*MAV_ODID_UA_TYPE*/byte ua_type; + [Description("GPS antenna lateral offset (table 2-36 of DO-282B)")] + //[FieldOffset(17)] + public /*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT*/byte gpsOffsetLat; - /// UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. + /// GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B) UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON [Units("")] - [Description("UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] uas_id; + [Description("GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)")] + //[FieldOffset(18)] + public /*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON*/byte gpsOffsetLon; + + /// ADS-B transponder reciever and transmit enable flags UAVIONIX_ADSB_OUT_RF_SELECT bitmask + [Units("")] + [Description("ADS-B transponder reciever and transmit enable flags")] + //[FieldOffset(19)] + public /*UAVIONIX_ADSB_OUT_RF_SELECT*/byte rfSelect; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=59)] - /// Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft. - public struct mavlink_open_drone_id_location_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=41)] + /// Dynamic data used to generate ADS-B out transponder data (send at 5Hz) + public struct mavlink_uavionix_adsb_out_dynamic_t { /// packet ordered constructor - public mavlink_open_drone_id_location_t(int latitude,int longitude,float altitude_barometric,float altitude_geodetic,float height,float timestamp,ushort direction,ushort speed_horizontal,short speed_vertical,byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_STATUS*/byte status,/*MAV_ODID_HEIGHT_REF*/byte height_reference,/*MAV_ODID_HOR_ACC*/byte horizontal_accuracy,/*MAV_ODID_VER_ACC*/byte vertical_accuracy,/*MAV_ODID_VER_ACC*/byte barometer_accuracy,/*MAV_ODID_SPEED_ACC*/byte speed_accuracy,/*MAV_ODID_TIME_ACC*/byte timestamp_accuracy) + public mavlink_uavionix_adsb_out_dynamic_t(uint utcTime,int gpsLat,int gpsLon,int gpsAlt,int baroAltMSL,uint accuracyHor,ushort accuracyVert,ushort accuracyVel,short velVert,short velNS,short VelEW,/*UAVIONIX_ADSB_OUT_DYNAMIC_STATE*/ushort state,ushort squawk,/*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX*/byte gpsFix,byte numSats,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus) { - this.latitude = latitude; - this.longitude = longitude; - this.altitude_barometric = altitude_barometric; - this.altitude_geodetic = altitude_geodetic; - this.height = height; - this.timestamp = timestamp; - this.direction = direction; - this.speed_horizontal = speed_horizontal; - this.speed_vertical = speed_vertical; - this.target_system = target_system; - this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.status = status; - this.height_reference = height_reference; - this.horizontal_accuracy = horizontal_accuracy; - this.vertical_accuracy = vertical_accuracy; - this.barometer_accuracy = barometer_accuracy; - this.speed_accuracy = speed_accuracy; - this.timestamp_accuracy = timestamp_accuracy; + this.utcTime = utcTime; + this.gpsLat = gpsLat; + this.gpsLon = gpsLon; + this.gpsAlt = gpsAlt; + this.baroAltMSL = baroAltMSL; + this.accuracyHor = accuracyHor; + this.accuracyVert = accuracyVert; + this.accuracyVel = accuracyVel; + this.velVert = velVert; + this.velNS = velNS; + this.VelEW = VelEW; + this.state = state; + this.squawk = squawk; + this.gpsFix = gpsFix; + this.numSats = numSats; + this.emergencyStatus = emergencyStatus; } /// packet xml order - public static mavlink_open_drone_id_location_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_STATUS*/byte status,ushort direction,ushort speed_horizontal,short speed_vertical,int latitude,int longitude,float altitude_barometric,float altitude_geodetic,/*MAV_ODID_HEIGHT_REF*/byte height_reference,float height,/*MAV_ODID_HOR_ACC*/byte horizontal_accuracy,/*MAV_ODID_VER_ACC*/byte vertical_accuracy,/*MAV_ODID_VER_ACC*/byte barometer_accuracy,/*MAV_ODID_SPEED_ACC*/byte speed_accuracy,float timestamp,/*MAV_ODID_TIME_ACC*/byte timestamp_accuracy) + public static mavlink_uavionix_adsb_out_dynamic_t PopulateXMLOrder(uint utcTime,int gpsLat,int gpsLon,int gpsAlt,/*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX*/byte gpsFix,byte numSats,int baroAltMSL,uint accuracyHor,ushort accuracyVert,ushort accuracyVel,short velVert,short velNS,short VelEW,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus,/*UAVIONIX_ADSB_OUT_DYNAMIC_STATE*/ushort state,ushort squawk) { - var msg = new mavlink_open_drone_id_location_t(); + var msg = new mavlink_uavionix_adsb_out_dynamic_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.status = status; - msg.direction = direction; - msg.speed_horizontal = speed_horizontal; - msg.speed_vertical = speed_vertical; - msg.latitude = latitude; - msg.longitude = longitude; - msg.altitude_barometric = altitude_barometric; - msg.altitude_geodetic = altitude_geodetic; - msg.height_reference = height_reference; - msg.height = height; - msg.horizontal_accuracy = horizontal_accuracy; - msg.vertical_accuracy = vertical_accuracy; - msg.barometer_accuracy = barometer_accuracy; - msg.speed_accuracy = speed_accuracy; - msg.timestamp = timestamp; - msg.timestamp_accuracy = timestamp_accuracy; + msg.utcTime = utcTime; + msg.gpsLat = gpsLat; + msg.gpsLon = gpsLon; + msg.gpsAlt = gpsAlt; + msg.gpsFix = gpsFix; + msg.numSats = numSats; + msg.baroAltMSL = baroAltMSL; + msg.accuracyHor = accuracyHor; + msg.accuracyVert = accuracyVert; + msg.accuracyVel = accuracyVel; + msg.velVert = velVert; + msg.velNS = velNS; + msg.VelEW = VelEW; + msg.emergencyStatus = emergencyStatus; + msg.state = state; + msg.squawk = squawk; return msg; } - /// Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). [degE7] - [Units("[degE7]")] - [Description("Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).")] + /// UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX [s] + [Units("[s]")] + [Description("UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX")] //[FieldOffset(0)] - public int latitude; + public uint utcTime; - /// Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). [degE7] + /// Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX [degE7] [Units("[degE7]")] - [Description("Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).")] + [Description("Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX")] //[FieldOffset(4)] - public int longitude; + public int gpsLat; - /// The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.")] + /// Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX [degE7] + [Units("[degE7]")] + [Description("Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX")] //[FieldOffset(8)] - public float altitude_barometric; + public int gpsLon; - /// The geodetic altitude as defined by WGS84. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("The geodetic altitude as defined by WGS84. If unknown: -1000 m.")] + /// Altitude (WGS84). UP +ve. If unknown set to INT32_MAX [mm] + [Units("[mm]")] + [Description("Altitude (WGS84). UP +ve. If unknown set to INT32_MAX")] //[FieldOffset(12)] - public float altitude_geodetic; + public int gpsAlt; - /// The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.")] + /// Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX [mbar] + [Units("[mbar]")] + [Description("Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX")] //[FieldOffset(16)] - public float height; + public int baroAltMSL; - /// Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. [s] - [Units("[s]")] - [Description("Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF.")] + /// Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX [mm] + [Units("[mm]")] + [Description("Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX")] //[FieldOffset(20)] - public float timestamp; + public uint accuracyHor; - /// Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. [cdeg] - [Units("[cdeg]")] - [Description("Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.")] + /// Vertical accuracy in cm. If unknown set to UINT16_MAX [cm] + [Units("[cm]")] + [Description("Vertical accuracy in cm. If unknown set to UINT16_MAX")] //[FieldOffset(24)] - public ushort direction; + public ushort accuracyVert; - /// Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. [cm/s] - [Units("[cm/s]")] - [Description("Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.")] + /// Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX [mm/s] + [Units("[mm/s]")] + [Description("Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX")] //[FieldOffset(26)] - public ushort speed_horizontal; + public ushort accuracyVel; - /// The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. [cm/s] + /// GPS vertical speed in cm/s. If unknown set to INT16_MAX [cm/s] [Units("[cm/s]")] - [Description("The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.")] + [Description("GPS vertical speed in cm/s. If unknown set to INT16_MAX")] //[FieldOffset(28)] - public short speed_vertical; + public short velVert; - /// System ID (0 for broadcast). - [Units("")] - [Description("System ID (0 for broadcast).")] + /// North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX [cm/s] + [Units("[cm/s]")] + [Description("North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX")] //[FieldOffset(30)] - public byte target_system; + public short velNS; - /// Component ID (0 for broadcast). + /// East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX [cm/s] + [Units("[cm/s]")] + [Description("East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX")] + //[FieldOffset(32)] + public short VelEW; + + /// ADS-B transponder dynamic input state flags UAVIONIX_ADSB_OUT_DYNAMIC_STATE bitmask [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(31)] - public byte target_component; + [Description("ADS-B transponder dynamic input state flags")] + //[FieldOffset(34)] + public /*UAVIONIX_ADSB_OUT_DYNAMIC_STATE*/ushort state; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + /// Mode A code (typically 1200 [0x04B0] for VFR) [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] - //[FieldOffset(32)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; + [Description("Mode A code (typically 1200 [0x04B0] for VFR)")] + //[FieldOffset(36)] + public ushort squawk; - /// Indicates whether the unmanned aircraft is on the ground or in the air. MAV_ODID_STATUS + /// 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX [Units("")] - [Description("Indicates whether the unmanned aircraft is on the ground or in the air.")] - //[FieldOffset(52)] - public /*MAV_ODID_STATUS*/byte status; + [Description("0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK")] + //[FieldOffset(38)] + public /*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX*/byte gpsFix; - /// Indicates the reference point for the height field. MAV_ODID_HEIGHT_REF + /// Number of satellites visible. If unknown set to UINT8_MAX [Units("")] - [Description("Indicates the reference point for the height field.")] - //[FieldOffset(53)] - public /*MAV_ODID_HEIGHT_REF*/byte height_reference; + [Description("Number of satellites visible. If unknown set to UINT8_MAX")] + //[FieldOffset(39)] + public byte numSats; - /// The accuracy of the horizontal position. MAV_ODID_HOR_ACC + /// Emergency status UAVIONIX_ADSB_EMERGENCY_STATUS [Units("")] - [Description("The accuracy of the horizontal position.")] - //[FieldOffset(54)] - public /*MAV_ODID_HOR_ACC*/byte horizontal_accuracy; + [Description("Emergency status")] + //[FieldOffset(40)] + public /*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus; + }; - /// The accuracy of the vertical position. MAV_ODID_VER_ACC + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] + /// Transceiver heartbeat with health report (updated every 10s) + public struct mavlink_uavionix_adsb_transceiver_health_report_t + { + /// packet ordered constructor + public mavlink_uavionix_adsb_transceiver_health_report_t(/*UAVIONIX_ADSB_RF_HEALTH*/byte rfHealth) + { + this.rfHealth = rfHealth; + + } + + /// packet xml order + public static mavlink_uavionix_adsb_transceiver_health_report_t PopulateXMLOrder(/*UAVIONIX_ADSB_RF_HEALTH*/byte rfHealth) + { + var msg = new mavlink_uavionix_adsb_transceiver_health_report_t(); + + msg.rfHealth = rfHealth; + + return msg; + } + + + /// ADS-B transponder messages UAVIONIX_ADSB_RF_HEALTH bitmask [Units("")] - [Description("The accuracy of the vertical position.")] - //[FieldOffset(55)] - public /*MAV_ODID_VER_ACC*/byte vertical_accuracy; + [Description("ADS-B transponder messages")] + //[FieldOffset(0)] + public /*UAVIONIX_ADSB_RF_HEALTH*/byte rfHealth; + }; - /// The accuracy of the barometric altitude. MAV_ODID_VER_ACC + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Aircraft Registration. + public struct mavlink_uavionix_adsb_out_cfg_registration_t + { + /// packet ordered constructor + public mavlink_uavionix_adsb_out_cfg_registration_t(byte[] registration) + { + this.registration = registration; + + } + + /// packet xml order + public static mavlink_uavionix_adsb_out_cfg_registration_t PopulateXMLOrder(byte[] registration) + { + var msg = new mavlink_uavionix_adsb_out_cfg_registration_t(); + + msg.registration = registration; + + return msg; + } + + + /// Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. 'N8644B '. Trailing spaces (0x20) only. This is null-terminated. [Units("")] - [Description("The accuracy of the barometric altitude.")] - //[FieldOffset(56)] - public /*MAV_ODID_VER_ACC*/byte barometer_accuracy; + [Description("Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. 'N8644B '. Trailing spaces (0x20) only. This is null-terminated.")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] + public byte[] registration; + }; - /// The accuracy of the horizontal and vertical speed. MAV_ODID_SPEED_ACC + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] + /// Flight Identification for ADSB-Out vehicles. + public struct mavlink_uavionix_adsb_out_cfg_flightid_t + { + /// packet ordered constructor + public mavlink_uavionix_adsb_out_cfg_flightid_t(byte[] flight_id) + { + this.flight_id = flight_id; + + } + + /// packet xml order + public static mavlink_uavionix_adsb_out_cfg_flightid_t PopulateXMLOrder(byte[] flight_id) + { + var msg = new mavlink_uavionix_adsb_out_cfg_flightid_t(); + + msg.flight_id = flight_id; + + return msg; + } + + + /// Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated. [Units("")] - [Description("The accuracy of the horizontal and vertical speed.")] - //[FieldOffset(57)] - public /*MAV_ODID_SPEED_ACC*/byte speed_accuracy; + [Description("Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] + public byte[] flight_id; + }; - /// The accuracy of the timestamps. MAV_ODID_TIME_ACC + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// Request messages. + public struct mavlink_uavionix_adsb_get_t + { + /// packet ordered constructor + public mavlink_uavionix_adsb_get_t(uint ReqMessageId) + { + this.ReqMessageId = ReqMessageId; + + } + + /// packet xml order + public static mavlink_uavionix_adsb_get_t PopulateXMLOrder(uint ReqMessageId) + { + var msg = new mavlink_uavionix_adsb_get_t(); + + msg.ReqMessageId = ReqMessageId; + + return msg; + } + + + /// Message ID to request. Supports any message in this 10000-10099 range [Units("")] - [Description("The accuracy of the timestamps.")] - //[FieldOffset(58)] - public /*MAV_ODID_TIME_ACC*/byte timestamp_accuracy; + [Description("Message ID to request. Supports any message in this 10000-10099 range")] + //[FieldOffset(0)] + public uint ReqMessageId; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] - /// Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes. - public struct mavlink_open_drone_id_authentication_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] + /// Control message with all data sent in UCP control message. + public struct mavlink_uavionix_adsb_out_control_t { /// packet ordered constructor - public mavlink_open_drone_id_authentication_t(uint timestamp,byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_AUTH_TYPE*/byte authentication_type,byte data_page,byte last_page_index,byte length,byte[] authentication_data) + public mavlink_uavionix_adsb_out_control_t(int baroAltMSL,ushort squawk,/*UAVIONIX_ADSB_OUT_CONTROL_STATE*/byte state,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus,byte[] flight_id,/*UAVIONIX_ADSB_XBIT*/byte x_bit) { - this.timestamp = timestamp; - this.target_system = target_system; - this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.authentication_type = authentication_type; - this.data_page = data_page; - this.last_page_index = last_page_index; - this.length = length; - this.authentication_data = authentication_data; + this.baroAltMSL = baroAltMSL; + this.squawk = squawk; + this.state = state; + this.emergencyStatus = emergencyStatus; + this.flight_id = flight_id; + this.x_bit = x_bit; } /// packet xml order - public static mavlink_open_drone_id_authentication_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_AUTH_TYPE*/byte authentication_type,byte data_page,byte last_page_index,byte length,uint timestamp,byte[] authentication_data) + public static mavlink_uavionix_adsb_out_control_t PopulateXMLOrder(/*UAVIONIX_ADSB_OUT_CONTROL_STATE*/byte state,int baroAltMSL,ushort squawk,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus,byte[] flight_id,/*UAVIONIX_ADSB_XBIT*/byte x_bit) { - var msg = new mavlink_open_drone_id_authentication_t(); + var msg = new mavlink_uavionix_adsb_out_control_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.authentication_type = authentication_type; - msg.data_page = data_page; - msg.last_page_index = last_page_index; - msg.length = length; - msg.timestamp = timestamp; - msg.authentication_data = authentication_data; + msg.state = state; + msg.baroAltMSL = baroAltMSL; + msg.squawk = squawk; + msg.emergencyStatus = emergencyStatus; + msg.flight_id = flight_id; + msg.x_bit = x_bit; return msg; } - /// This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. [s] - [Units("[s]")] - [Description("This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.")] + /// Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX [mbar] + [Units("[mbar]")] + [Description("Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX")] //[FieldOffset(0)] - public uint timestamp; + public int baroAltMSL; - /// System ID (0 for broadcast). + /// Mode A code (typically 1200 [0x04B0] for VFR) [Units("")] - [Description("System ID (0 for broadcast).")] + [Description("Mode A code (typically 1200 [0x04B0] for VFR)")] //[FieldOffset(4)] - public byte target_system; - - /// Component ID (0 for broadcast). - [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(5)] - public byte target_component; + public ushort squawk; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + /// ADS-B transponder control state flags UAVIONIX_ADSB_OUT_CONTROL_STATE bitmask [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] + [Description("ADS-B transponder control state flags")] //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; - - /// Indicates the type of authentication. MAV_ODID_AUTH_TYPE - [Units("")] - [Description("Indicates the type of authentication.")] - //[FieldOffset(26)] - public /*MAV_ODID_AUTH_TYPE*/byte authentication_type; + public /*UAVIONIX_ADSB_OUT_CONTROL_STATE*/byte state; - /// Allowed range is 0 - 15. + /// Emergency status UAVIONIX_ADSB_EMERGENCY_STATUS [Units("")] - [Description("Allowed range is 0 - 15.")] - //[FieldOffset(27)] - public byte data_page; + [Description("Emergency status")] + //[FieldOffset(7)] + public /*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus; - /// This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. + /// Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. [Units("")] - [Description("This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.")] - //[FieldOffset(28)] - public byte last_page_index; - - /// This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. [bytes] - [Units("[bytes]")] - [Description("This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.")] - //[FieldOffset(29)] - public byte length; + [Description("Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.")] + //[FieldOffset(8)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] flight_id; - /// Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. + /// X-Bit enable (military transponders only) UAVIONIX_ADSB_XBIT bitmask [Units("")] - [Description("Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.")] - //[FieldOffset(30)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=23)] - public byte[] authentication_data; + [Description("X-Bit enable (military transponders only)")] + //[FieldOffset(16)] + public /*UAVIONIX_ADSB_XBIT*/byte x_bit; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] - /// Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation. - public struct mavlink_open_drone_id_self_id_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// Status message with information from UCP Heartbeat and Status messages. + public struct mavlink_uavionix_adsb_out_status_t { /// packet ordered constructor - public mavlink_open_drone_id_self_id_t(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_DESC_TYPE*/byte description_type,byte[] description) + public mavlink_uavionix_adsb_out_status_t(ushort squawk,/*UAVIONIX_ADSB_OUT_STATUS_STATE*/byte state,/*UAVIONIX_ADSB_OUT_STATUS_NIC_NACP*/byte NIC_NACp,byte boardTemp,/*UAVIONIX_ADSB_OUT_STATUS_FAULT*/byte fault,byte[] flight_id) { - this.target_system = target_system; - this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.description_type = description_type; - this.description = description; + this.squawk = squawk; + this.state = state; + this.NIC_NACp = NIC_NACp; + this.boardTemp = boardTemp; + this.fault = fault; + this.flight_id = flight_id; } /// packet xml order - public static mavlink_open_drone_id_self_id_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_DESC_TYPE*/byte description_type,byte[] description) + public static mavlink_uavionix_adsb_out_status_t PopulateXMLOrder(/*UAVIONIX_ADSB_OUT_STATUS_STATE*/byte state,ushort squawk,/*UAVIONIX_ADSB_OUT_STATUS_NIC_NACP*/byte NIC_NACp,byte boardTemp,/*UAVIONIX_ADSB_OUT_STATUS_FAULT*/byte fault,byte[] flight_id) { - var msg = new mavlink_open_drone_id_self_id_t(); + var msg = new mavlink_uavionix_adsb_out_status_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.description_type = description_type; - msg.description = description; + msg.state = state; + msg.squawk = squawk; + msg.NIC_NACp = NIC_NACp; + msg.boardTemp = boardTemp; + msg.fault = fault; + msg.flight_id = flight_id; return msg; } - /// System ID (0 for broadcast). + /// Mode A code (typically 1200 [0x04B0] for VFR) [Units("")] - [Description("System ID (0 for broadcast).")] + [Description("Mode A code (typically 1200 [0x04B0] for VFR)")] //[FieldOffset(0)] - public byte target_system; + public ushort squawk; - /// Component ID (0 for broadcast). + /// ADS-B transponder status state flags UAVIONIX_ADSB_OUT_STATUS_STATE bitmask [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(1)] - public byte target_component; + [Description("ADS-B transponder status state flags")] + //[FieldOffset(2)] + public /*UAVIONIX_ADSB_OUT_STATUS_STATE*/byte state; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. + /// Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively UAVIONIX_ADSB_OUT_STATUS_NIC_NACP [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; + [Description("Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively")] + //[FieldOffset(3)] + public /*UAVIONIX_ADSB_OUT_STATUS_NIC_NACP*/byte NIC_NACp; - /// Indicates the type of the description field. MAV_ODID_DESC_TYPE + /// Board temperature in C [Units("")] - [Description("Indicates the type of the description field.")] - //[FieldOffset(22)] - public /*MAV_ODID_DESC_TYPE*/byte description_type; + [Description("Board temperature in C")] + //[FieldOffset(4)] + public byte boardTemp; - /// Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. + /// ADS-B transponder fault flags UAVIONIX_ADSB_OUT_STATUS_FAULT bitmask [Units("")] - [Description("Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.")] - //[FieldOffset(23)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=23)] - public byte[] description; + [Description("ADS-B transponder fault flags")] + //[FieldOffset(5)] + public /*UAVIONIX_ADSB_OUT_STATUS_FAULT*/byte fault; + + /// Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. + [Units("")] + [Description("Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.")] + //[FieldOffset(6)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] flight_id; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=54)] - /// Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information. - public struct mavlink_open_drone_id_system_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=85)] + /// Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit. + public struct mavlink_loweheiser_gov_efi_t { /// packet ordered constructor - public mavlink_open_drone_id_system_t(int operator_latitude,int operator_longitude,float area_ceiling,float area_floor,float operator_altitude_geo,uint timestamp,ushort area_count,ushort area_radius,byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_LOCATION_TYPE*/byte operator_location_type,/*MAV_ODID_CLASSIFICATION_TYPE*/byte classification_type,/*MAV_ODID_CATEGORY_EU*/byte category_eu,/*MAV_ODID_CLASS_EU*/byte class_eu) - { - this.operator_latitude = operator_latitude; - this.operator_longitude = operator_longitude; - this.area_ceiling = area_ceiling; - this.area_floor = area_floor; - this.operator_altitude_geo = operator_altitude_geo; - this.timestamp = timestamp; - this.area_count = area_count; - this.area_radius = area_radius; - this.target_system = target_system; - this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.operator_location_type = operator_location_type; - this.classification_type = classification_type; - this.category_eu = category_eu; - this.class_eu = class_eu; + public mavlink_loweheiser_gov_efi_t(float volt_batt,float curr_batt,float curr_gen,float curr_rot,float fuel_level,float throttle,uint runtime,int until_maintenance,float rectifier_temp,float generator_temp,float efi_batt,float efi_rpm,float efi_pw,float efi_fuel_flow,float efi_fuel_consumed,float efi_baro,float efi_mat,float efi_clt,float efi_tps,float efi_exhaust_gas_temperature,ushort generator_status,ushort efi_status,byte efi_index) + { + this.volt_batt = volt_batt; + this.curr_batt = curr_batt; + this.curr_gen = curr_gen; + this.curr_rot = curr_rot; + this.fuel_level = fuel_level; + this.throttle = throttle; + this.runtime = runtime; + this.until_maintenance = until_maintenance; + this.rectifier_temp = rectifier_temp; + this.generator_temp = generator_temp; + this.efi_batt = efi_batt; + this.efi_rpm = efi_rpm; + this.efi_pw = efi_pw; + this.efi_fuel_flow = efi_fuel_flow; + this.efi_fuel_consumed = efi_fuel_consumed; + this.efi_baro = efi_baro; + this.efi_mat = efi_mat; + this.efi_clt = efi_clt; + this.efi_tps = efi_tps; + this.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature; + this.generator_status = generator_status; + this.efi_status = efi_status; + this.efi_index = efi_index; } /// packet xml order - public static mavlink_open_drone_id_system_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_LOCATION_TYPE*/byte operator_location_type,/*MAV_ODID_CLASSIFICATION_TYPE*/byte classification_type,int operator_latitude,int operator_longitude,ushort area_count,ushort area_radius,float area_ceiling,float area_floor,/*MAV_ODID_CATEGORY_EU*/byte category_eu,/*MAV_ODID_CLASS_EU*/byte class_eu,float operator_altitude_geo,uint timestamp) + public static mavlink_loweheiser_gov_efi_t PopulateXMLOrder(float volt_batt,float curr_batt,float curr_gen,float curr_rot,float fuel_level,float throttle,uint runtime,int until_maintenance,float rectifier_temp,float generator_temp,float efi_batt,float efi_rpm,float efi_pw,float efi_fuel_flow,float efi_fuel_consumed,float efi_baro,float efi_mat,float efi_clt,float efi_tps,float efi_exhaust_gas_temperature,byte efi_index,ushort generator_status,ushort efi_status) { - var msg = new mavlink_open_drone_id_system_t(); + var msg = new mavlink_loweheiser_gov_efi_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.operator_location_type = operator_location_type; - msg.classification_type = classification_type; - msg.operator_latitude = operator_latitude; - msg.operator_longitude = operator_longitude; - msg.area_count = area_count; - msg.area_radius = area_radius; - msg.area_ceiling = area_ceiling; - msg.area_floor = area_floor; - msg.category_eu = category_eu; - msg.class_eu = class_eu; - msg.operator_altitude_geo = operator_altitude_geo; - msg.timestamp = timestamp; + msg.volt_batt = volt_batt; + msg.curr_batt = curr_batt; + msg.curr_gen = curr_gen; + msg.curr_rot = curr_rot; + msg.fuel_level = fuel_level; + msg.throttle = throttle; + msg.runtime = runtime; + msg.until_maintenance = until_maintenance; + msg.rectifier_temp = rectifier_temp; + msg.generator_temp = generator_temp; + msg.efi_batt = efi_batt; + msg.efi_rpm = efi_rpm; + msg.efi_pw = efi_pw; + msg.efi_fuel_flow = efi_fuel_flow; + msg.efi_fuel_consumed = efi_fuel_consumed; + msg.efi_baro = efi_baro; + msg.efi_mat = efi_mat; + msg.efi_clt = efi_clt; + msg.efi_tps = efi_tps; + msg.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature; + msg.efi_index = efi_index; + msg.generator_status = generator_status; + msg.efi_status = efi_status; return msg; } - /// Latitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] - [Units("[degE7]")] - [Description("Latitude of the operator. If unknown: 0 (both Lat/Lon).")] + /// Generator Battery voltage. [V] + [Units("[V]")] + [Description("Generator Battery voltage.")] //[FieldOffset(0)] - public int operator_latitude; + public float volt_batt; - /// Longitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] - [Units("[degE7]")] - [Description("Longitude of the operator. If unknown: 0 (both Lat/Lon).")] + /// Generator Battery current. [A] + [Units("[A]")] + [Description("Generator Battery current.")] //[FieldOffset(4)] - public int operator_longitude; + public float curr_batt; - /// Area Operations Ceiling relative to WGS84. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("Area Operations Ceiling relative to WGS84. If unknown: -1000 m.")] + /// Current being produced by generator. [A] + [Units("[A]")] + [Description("Current being produced by generator.")] //[FieldOffset(8)] - public float area_ceiling; + public float curr_gen; - /// Area Operations Floor relative to WGS84. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("Area Operations Floor relative to WGS84. If unknown: -1000 m.")] + /// Load current being consumed by the UAV (sum of curr_gen and curr_batt) [A] + [Units("[A]")] + [Description("Load current being consumed by the UAV (sum of curr_gen and curr_batt)")] //[FieldOffset(12)] - public float area_floor; + public float curr_rot; - /// Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.")] + /// Generator fuel remaining in litres. [l] + [Units("[l]")] + [Description("Generator fuel remaining in litres.")] //[FieldOffset(16)] - public float operator_altitude_geo; + public float fuel_level; - /// 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. [s] - [Units("[s]")] - [Description("32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.")] + /// Throttle Output. [%] + [Units("[%]")] + [Description("Throttle Output.")] //[FieldOffset(20)] - public uint timestamp; + public float throttle; - /// Number of aircraft in the area, group or formation (default 1). - [Units("")] - [Description("Number of aircraft in the area, group or formation (default 1).")] + /// Seconds this generator has run since it was rebooted. [s] + [Units("[s]")] + [Description("Seconds this generator has run since it was rebooted.")] //[FieldOffset(24)] - public ushort area_count; - - /// Radius of the cylindrical area of the group or formation (default 0). [m] - [Units("[m]")] - [Description("Radius of the cylindrical area of the group or formation (default 0).")] - //[FieldOffset(26)] - public ushort area_radius; + public uint runtime; - /// System ID (0 for broadcast). - [Units("")] - [Description("System ID (0 for broadcast).")] + /// Seconds until this generator requires maintenance. A negative value indicates maintenance is past due. [s] + [Units("[s]")] + [Description("Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.")] //[FieldOffset(28)] - public byte target_system; + public int until_maintenance; - /// Component ID (0 for broadcast). - [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(29)] - public byte target_component; + /// The Temperature of the rectifier. [degC] + [Units("[degC]")] + [Description("The Temperature of the rectifier.")] + //[FieldOffset(32)] + public float rectifier_temp; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] - //[FieldOffset(30)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; + /// The temperature of the mechanical motor, fuel cell core or generator. [degC] + [Units("[degC]")] + [Description("The temperature of the mechanical motor, fuel cell core or generator.")] + //[FieldOffset(36)] + public float generator_temp; - /// Specifies the operator location type. MAV_ODID_OPERATOR_LOCATION_TYPE + /// EFI Supply Voltage. [V] + [Units("[V]")] + [Description(" EFI Supply Voltage.")] + //[FieldOffset(40)] + public float efi_batt; + + /// Motor RPM. [rpm] + [Units("[rpm]")] + [Description("Motor RPM.")] + //[FieldOffset(44)] + public float efi_rpm; + + /// Injector pulse-width in miliseconds. [ms] + [Units("[ms]")] + [Description("Injector pulse-width in miliseconds.")] + //[FieldOffset(48)] + public float efi_pw; + + /// Fuel flow rate in litres/hour. [Units("")] - [Description("Specifies the operator location type.")] - //[FieldOffset(50)] - public /*MAV_ODID_OPERATOR_LOCATION_TYPE*/byte operator_location_type; + [Description("Fuel flow rate in litres/hour.")] + //[FieldOffset(52)] + public float efi_fuel_flow; - /// Specifies the classification type of the UA. MAV_ODID_CLASSIFICATION_TYPE + /// Fuel consumed. [l] + [Units("[l]")] + [Description("Fuel consumed.")] + //[FieldOffset(56)] + public float efi_fuel_consumed; + + /// Atmospheric pressure. [kPa] + [Units("[kPa]")] + [Description("Atmospheric pressure.")] + //[FieldOffset(60)] + public float efi_baro; + + /// Manifold Air Temperature. [degC] + [Units("[degC]")] + [Description("Manifold Air Temperature.")] + //[FieldOffset(64)] + public float efi_mat; + + /// Cylinder Head Temperature. [degC] + [Units("[degC]")] + [Description("Cylinder Head Temperature.")] + //[FieldOffset(68)] + public float efi_clt; + + /// Throttle Position. [%] + [Units("[%]")] + [Description("Throttle Position.")] + //[FieldOffset(72)] + public float efi_tps; + + /// Exhaust gas temperature. [degC] + [Units("[degC]")] + [Description("Exhaust gas temperature.")] + //[FieldOffset(76)] + public float efi_exhaust_gas_temperature; + + /// Generator status. [Units("")] - [Description("Specifies the classification type of the UA.")] - //[FieldOffset(51)] - public /*MAV_ODID_CLASSIFICATION_TYPE*/byte classification_type; + [Description("Generator status.")] + //[FieldOffset(80)] + public ushort generator_status; - /// When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. MAV_ODID_CATEGORY_EU + /// EFI status. [Units("")] - [Description("When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.")] - //[FieldOffset(52)] - public /*MAV_ODID_CATEGORY_EU*/byte category_eu; + [Description("EFI status.")] + //[FieldOffset(82)] + public ushort efi_status; - /// When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. MAV_ODID_CLASS_EU + /// EFI index. [Units("")] - [Description("When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.")] - //[FieldOffset(53)] - public /*MAV_ODID_CLASS_EU*/byte class_eu; + [Description("EFI index.")] + //[FieldOffset(84)] + public byte efi_index; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=43)] - /// Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID. - public struct mavlink_open_drone_id_operator_id_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] + /// Message reporting the current status of a gimbal device. This message should be broadcasted by a gimbal device component at a low regular rate (e.g. 4 Hz). For higher rates it should be emitted with a target. + public struct mavlink_storm32_gimbal_device_status_t { /// packet ordered constructor - public mavlink_open_drone_id_operator_id_t(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_ID_TYPE*/byte operator_id_type,byte[] operator_id) + public mavlink_storm32_gimbal_device_status_t(uint time_boot_ms,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,float yaw_absolute,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort flags,/*GIMBAL_DEVICE_ERROR_FLAGS*/ushort failure_flags,byte target_system,byte target_component) { + this.time_boot_ms = time_boot_ms; + 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.yaw_absolute = yaw_absolute; + this.flags = flags; + this.failure_flags = failure_flags; this.target_system = target_system; this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.operator_id_type = operator_id_type; - this.operator_id = operator_id; } /// packet xml order - public static mavlink_open_drone_id_operator_id_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,/*MAV_ODID_OPERATOR_ID_TYPE*/byte operator_id_type,byte[] operator_id) + public static mavlink_storm32_gimbal_device_status_t PopulateXMLOrder(byte target_system,byte target_component,uint time_boot_ms,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,float yaw_absolute,/*GIMBAL_DEVICE_ERROR_FLAGS*/ushort failure_flags) { - var msg = new mavlink_open_drone_id_operator_id_t(); + var msg = new mavlink_storm32_gimbal_device_status_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.operator_id_type = operator_id_type; - msg.operator_id = operator_id; + msg.time_boot_ms = time_boot_ms; + msg.flags = flags; + 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.yaw_absolute = yaw_absolute; + msg.failure_flags = failure_flags; return msg; } - /// System ID (0 for broadcast). - [Units("")] - [Description("System ID (0 for broadcast).")] + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] //[FieldOffset(0)] - public byte target_system; + public uint time_boot_ms; - /// Component ID (0 for broadcast). + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag. [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(1)] - public byte target_component; + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag.")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; + /// X component of angular velocity (NaN if unknown). [rad/s] + [Units("[rad/s]")] + [Description("X component of angular velocity (NaN if unknown).")] + //[FieldOffset(20)] + public float angular_velocity_x; - /// Indicates the type of the operator_id field. MAV_ODID_OPERATOR_ID_TYPE - [Units("")] - [Description("Indicates the type of the operator_id field.")] - //[FieldOffset(22)] - public /*MAV_ODID_OPERATOR_ID_TYPE*/byte operator_id_type; + /// Y component of angular velocity (NaN if unknown). [rad/s] + [Units("[rad/s]")] + [Description("Y component of angular velocity (NaN if unknown).")] + //[FieldOffset(24)] + public float angular_velocity_y; - /// Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - [Units("")] - [Description("Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.")] - //[FieldOffset(23)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] operator_id; - }; + /// Z component of angular velocity (the frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN if unknown). [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity (the frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN if unknown).")] + //[FieldOffset(28)] + public float angular_velocity_z; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] - /// Status from the transmitter telling the flight controller if the remote ID system is ready for arming. - public struct mavlink_open_drone_id_arm_status_t - { - /// packet ordered constructor - public mavlink_open_drone_id_arm_status_t(/*MAV_ODID_ARM_STATUS*/byte status,byte[] error) - { - this.status = status; - this.error = error; - - } - - /// packet xml order - public static mavlink_open_drone_id_arm_status_t PopulateXMLOrder(/*MAV_ODID_ARM_STATUS*/byte status,byte[] error) - { - var msg = new mavlink_open_drone_id_arm_status_t(); + /// Yaw in absolute frame relative to Earth's North, north is 0 (NaN if unknown). [deg] + [Units("[deg]")] + [Description("Yaw in absolute frame relative to Earth's North, north is 0 (NaN if unknown).")] + //[FieldOffset(32)] + public float yaw_absolute; - msg.status = status; - msg.error = error; - - return msg; - } - + /// Gimbal device flags currently applied. MAV_STORM32_GIMBAL_DEVICE_FLAGS + [Units("")] + [Description("Gimbal device flags currently applied.")] + //[FieldOffset(36)] + public /*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort flags; - /// Status level indicating if arming is allowed. MAV_ODID_ARM_STATUS + /// Failure flags (0 for no failure). GIMBAL_DEVICE_ERROR_FLAGS bitmask [Units("")] - [Description("Status level indicating if arming is allowed.")] - //[FieldOffset(0)] - public /*MAV_ODID_ARM_STATUS*/byte status; + [Description("Failure flags (0 for no failure).")] + //[FieldOffset(38)] + public /*GIMBAL_DEVICE_ERROR_FLAGS*/ushort failure_flags; - /// Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. + /// System ID [Units("")] - [Description("Text error message, should be empty if status is good to arm. Fill with nulls in unused portion.")] - //[FieldOffset(1)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] - public byte[] error; + [Description("System ID")] + //[FieldOffset(40)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(41)] + public byte target_component; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=249)] - /// An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon. - public struct mavlink_open_drone_id_message_pack_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] + /// Message to a gimbal device to control its attitude. This message is to be sent from the gimbal manager to the gimbal device. Angles and rates can be set to NaN according to use case. + public struct mavlink_storm32_gimbal_device_control_t { /// packet ordered constructor - public mavlink_open_drone_id_message_pack_t(byte target_system,byte target_component,byte[] id_or_mac,byte single_message_size,byte msg_pack_size,byte[] messages) + public mavlink_storm32_gimbal_device_control_t(float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component) { + 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.flags = flags; this.target_system = target_system; this.target_component = target_component; - this.id_or_mac = id_or_mac; - this.single_message_size = single_message_size; - this.msg_pack_size = msg_pack_size; - this.messages = messages; } /// packet xml order - public static mavlink_open_drone_id_message_pack_t PopulateXMLOrder(byte target_system,byte target_component,byte[] id_or_mac,byte single_message_size,byte msg_pack_size,byte[] messages) + public static mavlink_storm32_gimbal_device_control_t PopulateXMLOrder(byte target_system,byte target_component,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) { - var msg = new mavlink_open_drone_id_message_pack_t(); + var msg = new mavlink_storm32_gimbal_device_control_t(); msg.target_system = target_system; msg.target_component = target_component; - msg.id_or_mac = id_or_mac; - msg.single_message_size = single_message_size; - msg.msg_pack_size = msg_pack_size; - msg.messages = messages; + msg.flags = flags; + 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; } - /// System ID (0 for broadcast). + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, set first element to NaN to be ignored). [Units("")] - [Description("System ID (0 for broadcast).")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, set first element to NaN to be ignored).")] //[FieldOffset(0)] - public byte target_system; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Component ID (0 for broadcast). - [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(1)] - public byte target_component; + /// X component of angular velocity (positive: roll to the right, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("X component of angular velocity (positive: roll to the right, NaN to be ignored).")] + //[FieldOffset(16)] + public float angular_velocity_x; - /// Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - [Units("")] - [Description("Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. ")] - //[FieldOffset(2)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] id_or_mac; + /// Y component of angular velocity (positive: tilt up, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Y component of angular velocity (positive: tilt up, NaN to be ignored).")] + //[FieldOffset(20)] + public float angular_velocity_y; - /// This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length. [bytes] - [Units("[bytes]")] - [Description("This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.")] - //[FieldOffset(22)] - public byte single_message_size; + /// Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).")] + //[FieldOffset(24)] + public float angular_velocity_z; - /// Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. + /// Gimbal device flags (UINT16_MAX to be ignored). MAV_STORM32_GIMBAL_DEVICE_FLAGS [Units("")] - [Description("Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.")] - //[FieldOffset(23)] - public byte msg_pack_size; + [Description("Gimbal device flags (UINT16_MAX to be ignored).")] + //[FieldOffset(28)] + public /*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort flags; - /// Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. + /// System ID [Units("")] - [Description("Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.")] - //[FieldOffset(24)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=225)] - public byte[] messages; + [Description("System ID")] + //[FieldOffset(30)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(31)] + public byte target_component; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - /// Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location. - public struct mavlink_open_drone_id_system_update_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// Information about a gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. It mirrors some fields of the STORM32_GIMBAL_DEVICE_INFORMATION message, but not all. If the additional information is desired, also STORM32_GIMBAL_DEVICE_INFORMATION should be requested. + public struct mavlink_storm32_gimbal_manager_information_t { /// packet ordered constructor - public mavlink_open_drone_id_system_update_t(int operator_latitude,int operator_longitude,float operator_altitude_geo,uint timestamp,byte target_system,byte target_component) + public mavlink_storm32_gimbal_manager_information_t(/*MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS*/uint device_cap_flags,/*MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS*/uint manager_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,byte gimbal_id) { - this.operator_latitude = operator_latitude; - this.operator_longitude = operator_longitude; - this.operator_altitude_geo = operator_altitude_geo; - this.timestamp = timestamp; - this.target_system = target_system; - this.target_component = target_component; + this.device_cap_flags = device_cap_flags; + this.manager_cap_flags = manager_cap_flags; + this.roll_min = roll_min; + this.roll_max = roll_max; + this.pitch_min = pitch_min; + this.pitch_max = pitch_max; + this.yaw_min = yaw_min; + this.yaw_max = yaw_max; + this.gimbal_id = gimbal_id; } /// packet xml order - public static mavlink_open_drone_id_system_update_t PopulateXMLOrder(byte target_system,byte target_component,int operator_latitude,int operator_longitude,float operator_altitude_geo,uint timestamp) + public static mavlink_storm32_gimbal_manager_information_t PopulateXMLOrder(byte gimbal_id,/*MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS*/uint device_cap_flags,/*MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS*/uint manager_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) { - var msg = new mavlink_open_drone_id_system_update_t(); + var msg = new mavlink_storm32_gimbal_manager_information_t(); - msg.target_system = target_system; - msg.target_component = target_component; - msg.operator_latitude = operator_latitude; - msg.operator_longitude = operator_longitude; - msg.operator_altitude_geo = operator_altitude_geo; - msg.timestamp = timestamp; + msg.gimbal_id = gimbal_id; + msg.device_cap_flags = device_cap_flags; + msg.manager_cap_flags = manager_cap_flags; + msg.roll_min = roll_min; + msg.roll_max = roll_max; + msg.pitch_min = pitch_min; + msg.pitch_max = pitch_max; + msg.yaw_min = yaw_min; + msg.yaw_max = yaw_max; return msg; } - /// Latitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] - [Units("[degE7]")] - [Description("Latitude of the operator. If unknown: 0 (both Lat/Lon).")] + /// Gimbal device capability flags. MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS bitmask + [Units("")] + [Description("Gimbal device capability flags.")] //[FieldOffset(0)] - public int operator_latitude; + public /*MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS*/uint device_cap_flags; - /// Longitude of the operator. If unknown: 0 (both Lat/Lon). [degE7] - [Units("[degE7]")] - [Description("Longitude of the operator. If unknown: 0 (both Lat/Lon).")] + /// Gimbal manager capability flags. MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS bitmask + [Units("")] + [Description("Gimbal manager capability flags.")] //[FieldOffset(4)] - public int operator_longitude; + public /*MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS*/uint manager_cap_flags; - /// Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. [m] - [Units("[m]")] - [Description("Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.")] + /// Hardware minimum roll angle (positive: roll to the right, NaN if unknown). [rad] + [Units("[rad]")] + [Description("Hardware minimum roll angle (positive: roll to the right, NaN if unknown).")] //[FieldOffset(8)] - public float operator_altitude_geo; + public float roll_min; - /// 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. [s] - [Units("[s]")] - [Description("32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.")] + /// Hardware maximum roll angle (positive: roll to the right, NaN if unknown). [rad] + [Units("[rad]")] + [Description("Hardware maximum roll angle (positive: roll to the right, NaN if unknown).")] //[FieldOffset(12)] - public uint timestamp; + public float roll_max; - /// System ID (0 for broadcast). - [Units("")] - [Description("System ID (0 for broadcast).")] + /// Hardware minimum pitch/tilt angle (positive: tilt up, NaN if unknown). [rad] + [Units("[rad]")] + [Description("Hardware minimum pitch/tilt angle (positive: tilt up, NaN if unknown).")] //[FieldOffset(16)] - public byte target_system; + public float pitch_min; + + /// Hardware maximum pitch/tilt angle (positive: tilt up, NaN if unknown). [rad] + [Units("[rad]")] + [Description("Hardware maximum pitch/tilt angle (positive: tilt up, NaN if unknown).")] + //[FieldOffset(20)] + public float pitch_max; + + /// Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown). [rad] + [Units("[rad]")] + [Description("Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown).")] + //[FieldOffset(24)] + public float yaw_min; + + /// Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown). [rad] + [Units("[rad]")] + [Description("Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown).")] + //[FieldOffset(28)] + public float yaw_max; - /// Component ID (0 for broadcast). + /// Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. [Units("")] - [Description("Component ID (0 for broadcast).")] - //[FieldOffset(17)] - public byte target_component; + [Description("Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.")] + //[FieldOffset(32)] + public byte gimbal_id; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)] - /// Temperature and humidity from hygrometer. - public struct mavlink_hygrometer_sensor_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=7)] + /// Message reporting the current status of a gimbal manager. This message should be broadcast at a low regular rate (e.g. 1 Hz, may be increase momentarily to e.g. 5 Hz for a period of 1 sec after a change). + public struct mavlink_storm32_gimbal_manager_status_t { /// packet ordered constructor - public mavlink_hygrometer_sensor_t(short temperature,ushort humidity,byte id) + public mavlink_storm32_gimbal_manager_status_t(/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags,/*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte supervisor,/*MAV_STORM32_GIMBAL_MANAGER_PROFILE*/byte profile) { - this.temperature = temperature; - this.humidity = humidity; - this.id = id; + this.device_flags = device_flags; + this.manager_flags = manager_flags; + this.gimbal_id = gimbal_id; + this.supervisor = supervisor; + this.profile = profile; } /// packet xml order - public static mavlink_hygrometer_sensor_t PopulateXMLOrder(byte id,short temperature,ushort humidity) + public static mavlink_storm32_gimbal_manager_status_t PopulateXMLOrder(byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte supervisor,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags,/*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags,/*MAV_STORM32_GIMBAL_MANAGER_PROFILE*/byte profile) { - var msg = new mavlink_hygrometer_sensor_t(); + var msg = new mavlink_storm32_gimbal_manager_status_t(); - msg.id = id; - msg.temperature = temperature; - msg.humidity = humidity; + msg.gimbal_id = gimbal_id; + msg.supervisor = supervisor; + msg.device_flags = device_flags; + msg.manager_flags = manager_flags; + msg.profile = profile; return msg; } - /// Temperature [cdegC] - [Units("[cdegC]")] - [Description("Temperature")] + /// Gimbal device flags currently applied. MAV_STORM32_GIMBAL_DEVICE_FLAGS + [Units("")] + [Description("Gimbal device flags currently applied.")] //[FieldOffset(0)] - public short temperature; + public /*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags; - /// Humidity [c%] - [Units("[c%]")] - [Description("Humidity")] + /// Gimbal manager flags currently applied. MAV_STORM32_GIMBAL_MANAGER_FLAGS + [Units("")] + [Description("Gimbal manager flags currently applied.")] //[FieldOffset(2)] - public ushort humidity; + public /*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags; - /// Hygrometer ID + /// Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. [Units("")] - [Description("Hygrometer ID")] + [Description("Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.")] //[FieldOffset(4)] - public byte id; + public byte gimbal_id; + + /// Client who is currently supervisor (0 = none). MAV_STORM32_GIMBAL_MANAGER_CLIENT + [Units("")] + [Description("Client who is currently supervisor (0 = none).")] + //[FieldOffset(5)] + public /*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte supervisor; + + /// Profile currently applied (0 = default). MAV_STORM32_GIMBAL_MANAGER_PROFILE + [Units("")] + [Description("Profile currently applied (0 = default).")] + //[FieldOffset(6)] + public /*MAV_STORM32_GIMBAL_MANAGER_PROFILE*/byte profile; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - /// Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter) - public struct mavlink_uavionix_adsb_out_cfg_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)] + /// Message to a gimbal manager to control the gimbal attitude. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. + public struct mavlink_storm32_gimbal_manager_control_t { /// packet ordered constructor - public mavlink_uavionix_adsb_out_cfg_t(uint ICAO,ushort stallSpeed,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitterType,/*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE*/byte aircraftSize,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT*/byte gpsOffsetLat,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON*/byte gpsOffsetLon,/*UAVIONIX_ADSB_OUT_RF_SELECT*/byte rfSelect) + public mavlink_storm32_gimbal_manager_control_t(float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags,/*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags,byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client) { - this.ICAO = ICAO; - this.stallSpeed = stallSpeed; - this.callsign = callsign; - this.emitterType = emitterType; - this.aircraftSize = aircraftSize; - this.gpsOffsetLat = gpsOffsetLat; - this.gpsOffsetLon = gpsOffsetLon; - this.rfSelect = rfSelect; + 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.device_flags = device_flags; + this.manager_flags = manager_flags; + this.target_system = target_system; + this.target_component = target_component; + this.gimbal_id = gimbal_id; + this.client = client; } /// packet xml order - public static mavlink_uavionix_adsb_out_cfg_t PopulateXMLOrder(uint ICAO,byte[] callsign,/*ADSB_EMITTER_TYPE*/byte emitterType,/*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE*/byte aircraftSize,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT*/byte gpsOffsetLat,/*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON*/byte gpsOffsetLon,ushort stallSpeed,/*UAVIONIX_ADSB_OUT_RF_SELECT*/byte rfSelect) + public static mavlink_storm32_gimbal_manager_control_t PopulateXMLOrder(byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags,/*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) { - var msg = new mavlink_uavionix_adsb_out_cfg_t(); + var msg = new mavlink_storm32_gimbal_manager_control_t(); - msg.ICAO = ICAO; - msg.callsign = callsign; - msg.emitterType = emitterType; - msg.aircraftSize = aircraftSize; - msg.gpsOffsetLat = gpsOffsetLat; - msg.gpsOffsetLon = gpsOffsetLon; - msg.stallSpeed = stallSpeed; - msg.rfSelect = rfSelect; + msg.target_system = target_system; + msg.target_component = target_component; + msg.gimbal_id = gimbal_id; + msg.client = client; + msg.device_flags = device_flags; + msg.manager_flags = manager_flags; + 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; } - /// Vehicle address (24 bit) + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the GIMBAL_MANAGER_FLAGS_ABSOLUTE_YAW flag, set first element to NaN to be ignored). [Units("")] - [Description("Vehicle address (24 bit)")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the GIMBAL_MANAGER_FLAGS_ABSOLUTE_YAW flag, set first element to NaN to be ignored).")] //[FieldOffset(0)] - public uint ICAO; + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; - /// Aircraft stall speed in cm/s [cm/s] - [Units("[cm/s]")] - [Description("Aircraft stall speed in cm/s")] - //[FieldOffset(4)] - public ushort stallSpeed; + /// X component of angular velocity (positive: roll to the right, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("X component of angular velocity (positive: roll to the right, NaN to be ignored).")] + //[FieldOffset(16)] + public float angular_velocity_x; - /// Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, ' ' only) + /// Y component of angular velocity (positive: tilt up, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Y component of angular velocity (positive: tilt up, NaN to be ignored).")] + //[FieldOffset(20)] + public float angular_velocity_y; + + /// Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).")] + //[FieldOffset(24)] + public float angular_velocity_z; + + /// Gimbal device flags (UINT16_MAX to be ignored). MAV_STORM32_GIMBAL_DEVICE_FLAGS [Units("")] - [Description("Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, ' ' only)")] - //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] - public byte[] callsign; + [Description("Gimbal device flags (UINT16_MAX to be ignored).")] + //[FieldOffset(28)] + public /*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags; - /// Transmitting vehicle type. See ADSB_EMITTER_TYPE enum ADSB_EMITTER_TYPE + /// Gimbal manager flags (0 to be ignored). MAV_STORM32_GIMBAL_MANAGER_FLAGS [Units("")] - [Description("Transmitting vehicle type. See ADSB_EMITTER_TYPE enum")] - //[FieldOffset(15)] - public /*ADSB_EMITTER_TYPE*/byte emitterType; + [Description("Gimbal manager flags (0 to be ignored).")] + //[FieldOffset(30)] + public /*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags; - /// Aircraft length and width encoding (table 2-35 of DO-282B) UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE + /// System ID [Units("")] - [Description("Aircraft length and width encoding (table 2-35 of DO-282B)")] - //[FieldOffset(16)] - public /*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE*/byte aircraftSize; + [Description("System ID")] + //[FieldOffset(32)] + public byte target_system; - /// GPS antenna lateral offset (table 2-36 of DO-282B) UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT + /// Component ID [Units("")] - [Description("GPS antenna lateral offset (table 2-36 of DO-282B)")] - //[FieldOffset(17)] - public /*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT*/byte gpsOffsetLat; + [Description("Component ID")] + //[FieldOffset(33)] + public byte target_component; - /// GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B) UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON + /// Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). [Units("")] - [Description("GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)")] - //[FieldOffset(18)] - public /*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON*/byte gpsOffsetLon; + [Description("Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).")] + //[FieldOffset(34)] + public byte gimbal_id; - /// ADS-B transponder reciever and transmit enable flags UAVIONIX_ADSB_OUT_RF_SELECT bitmask + /// Client which is contacting the gimbal manager (must be set). MAV_STORM32_GIMBAL_MANAGER_CLIENT [Units("")] - [Description("ADS-B transponder reciever and transmit enable flags")] - //[FieldOffset(19)] - public /*UAVIONIX_ADSB_OUT_RF_SELECT*/byte rfSelect; + [Description("Client which is contacting the gimbal manager (must be set).")] + //[FieldOffset(35)] + public /*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=41)] - /// Dynamic data used to generate ADS-B out transponder data (send at 5Hz) - public struct mavlink_uavionix_adsb_out_dynamic_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// Message to a gimbal manager to control the gimbal tilt and pan angles. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. + public struct mavlink_storm32_gimbal_manager_control_pitchyaw_t { /// packet ordered constructor - public mavlink_uavionix_adsb_out_dynamic_t(uint utcTime,int gpsLat,int gpsLon,int gpsAlt,int baroAltMSL,uint accuracyHor,ushort accuracyVert,ushort accuracyVel,short velVert,short velNS,short VelEW,/*UAVIONIX_ADSB_OUT_DYNAMIC_STATE*/ushort state,ushort squawk,/*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX*/byte gpsFix,byte numSats,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus) + public mavlink_storm32_gimbal_manager_control_pitchyaw_t(float pitch,float yaw,float pitch_rate,float yaw_rate,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags,/*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags,byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client) { - this.utcTime = utcTime; - this.gpsLat = gpsLat; - this.gpsLon = gpsLon; - this.gpsAlt = gpsAlt; - this.baroAltMSL = baroAltMSL; - this.accuracyHor = accuracyHor; - this.accuracyVert = accuracyVert; - this.accuracyVel = accuracyVel; - this.velVert = velVert; - this.velNS = velNS; - this.VelEW = VelEW; - this.state = state; - this.squawk = squawk; - this.gpsFix = gpsFix; - this.numSats = numSats; - this.emergencyStatus = emergencyStatus; + this.pitch = pitch; + this.yaw = yaw; + this.pitch_rate = pitch_rate; + this.yaw_rate = yaw_rate; + this.device_flags = device_flags; + this.manager_flags = manager_flags; + this.target_system = target_system; + this.target_component = target_component; + this.gimbal_id = gimbal_id; + this.client = client; } /// packet xml order - public static mavlink_uavionix_adsb_out_dynamic_t PopulateXMLOrder(uint utcTime,int gpsLat,int gpsLon,int gpsAlt,/*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX*/byte gpsFix,byte numSats,int baroAltMSL,uint accuracyHor,ushort accuracyVert,ushort accuracyVel,short velVert,short velNS,short VelEW,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus,/*UAVIONIX_ADSB_OUT_DYNAMIC_STATE*/ushort state,ushort squawk) + public static mavlink_storm32_gimbal_manager_control_pitchyaw_t PopulateXMLOrder(byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client,/*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags,/*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags,float pitch,float yaw,float pitch_rate,float yaw_rate) { - var msg = new mavlink_uavionix_adsb_out_dynamic_t(); + var msg = new mavlink_storm32_gimbal_manager_control_pitchyaw_t(); - msg.utcTime = utcTime; - msg.gpsLat = gpsLat; - msg.gpsLon = gpsLon; - msg.gpsAlt = gpsAlt; - msg.gpsFix = gpsFix; - msg.numSats = numSats; - msg.baroAltMSL = baroAltMSL; - msg.accuracyHor = accuracyHor; - msg.accuracyVert = accuracyVert; - msg.accuracyVel = accuracyVel; - msg.velVert = velVert; - msg.velNS = velNS; - msg.VelEW = VelEW; - msg.emergencyStatus = emergencyStatus; - msg.state = state; - msg.squawk = squawk; + msg.target_system = target_system; + msg.target_component = target_component; + msg.gimbal_id = gimbal_id; + msg.client = client; + msg.device_flags = device_flags; + msg.manager_flags = manager_flags; + msg.pitch = pitch; + msg.yaw = yaw; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; return msg; } - /// UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX [s] - [Units("[s]")] - [Description("UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX")] + /// Pitch/tilt angle (positive: tilt up, NaN to be ignored). [rad] + [Units("[rad]")] + [Description("Pitch/tilt angle (positive: tilt up, NaN to be ignored).")] //[FieldOffset(0)] - public uint utcTime; + public float pitch; - /// Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX [degE7] - [Units("[degE7]")] - [Description("Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX")] + /// Yaw/pan angle (positive: pan the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). [rad] + [Units("[rad]")] + [Description("Yaw/pan angle (positive: pan the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).")] //[FieldOffset(4)] - public int gpsLat; + public float yaw; - /// Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX [degE7] - [Units("[degE7]")] - [Description("Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX")] + /// Pitch/tilt angular rate (positive: tilt up, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Pitch/tilt angular rate (positive: tilt up, NaN to be ignored).")] //[FieldOffset(8)] - public int gpsLon; + public float pitch_rate; - /// Altitude (WGS84). UP +ve. If unknown set to INT32_MAX [mm] - [Units("[mm]")] - [Description("Altitude (WGS84). UP +ve. If unknown set to INT32_MAX")] + /// Yaw/pan angular rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Yaw/pan angular rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).")] //[FieldOffset(12)] - public int gpsAlt; + public float yaw_rate; - /// Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX [mbar] - [Units("[mbar]")] - [Description("Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX")] + /// Gimbal device flags (UINT16_MAX to be ignored). MAV_STORM32_GIMBAL_DEVICE_FLAGS + [Units("")] + [Description("Gimbal device flags (UINT16_MAX to be ignored).")] //[FieldOffset(16)] - public int baroAltMSL; - - /// Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX [mm] - [Units("[mm]")] - [Description("Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX")] - //[FieldOffset(20)] - public uint accuracyHor; - - /// Vertical accuracy in cm. If unknown set to UINT16_MAX [cm] - [Units("[cm]")] - [Description("Vertical accuracy in cm. If unknown set to UINT16_MAX")] - //[FieldOffset(24)] - public ushort accuracyVert; - - /// Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX [mm/s] - [Units("[mm/s]")] - [Description("Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX")] - //[FieldOffset(26)] - public ushort accuracyVel; - - /// GPS vertical speed in cm/s. If unknown set to INT16_MAX [cm/s] - [Units("[cm/s]")] - [Description("GPS vertical speed in cm/s. If unknown set to INT16_MAX")] - //[FieldOffset(28)] - public short velVert; - - /// North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX [cm/s] - [Units("[cm/s]")] - [Description("North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX")] - //[FieldOffset(30)] - public short velNS; - - /// East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX [cm/s] - [Units("[cm/s]")] - [Description("East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX")] - //[FieldOffset(32)] - public short VelEW; + public /*MAV_STORM32_GIMBAL_DEVICE_FLAGS*/ushort device_flags; - /// ADS-B transponder dynamic input state flags UAVIONIX_ADSB_OUT_DYNAMIC_STATE bitmask + /// Gimbal manager flags (0 to be ignored). MAV_STORM32_GIMBAL_MANAGER_FLAGS [Units("")] - [Description("ADS-B transponder dynamic input state flags")] - //[FieldOffset(34)] - public /*UAVIONIX_ADSB_OUT_DYNAMIC_STATE*/ushort state; + [Description("Gimbal manager flags (0 to be ignored).")] + //[FieldOffset(18)] + public /*MAV_STORM32_GIMBAL_MANAGER_FLAGS*/ushort manager_flags; - /// Mode A code (typically 1200 [0x04B0] for VFR) + /// System ID [Units("")] - [Description("Mode A code (typically 1200 [0x04B0] for VFR)")] - //[FieldOffset(36)] - public ushort squawk; + [Description("System ID")] + //[FieldOffset(20)] + public byte target_system; - /// 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX + /// Component ID [Units("")] - [Description("0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK")] - //[FieldOffset(38)] - public /*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX*/byte gpsFix; + [Description("Component ID")] + //[FieldOffset(21)] + public byte target_component; - /// Number of satellites visible. If unknown set to UINT8_MAX + /// Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). [Units("")] - [Description("Number of satellites visible. If unknown set to UINT8_MAX")] - //[FieldOffset(39)] - public byte numSats; + [Description("Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).")] + //[FieldOffset(22)] + public byte gimbal_id; - /// Emergency status UAVIONIX_ADSB_EMERGENCY_STATUS + /// Client which is contacting the gimbal manager (must be set). MAV_STORM32_GIMBAL_MANAGER_CLIENT [Units("")] - [Description("Emergency status")] - //[FieldOffset(40)] - public /*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus; + [Description("Client which is contacting the gimbal manager (must be set).")] + //[FieldOffset(23)] + public /*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] - /// Transceiver heartbeat with health report (updated every 10s) - public struct mavlink_uavionix_adsb_transceiver_health_report_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Message to a gimbal manager to correct the gimbal roll angle. This message is typically used to manually correct for a tilted horizon in operation. A gimbal device is never to react to this message. + public struct mavlink_storm32_gimbal_manager_correct_roll_t { /// packet ordered constructor - public mavlink_uavionix_adsb_transceiver_health_report_t(/*UAVIONIX_ADSB_RF_HEALTH*/byte rfHealth) + public mavlink_storm32_gimbal_manager_correct_roll_t(float roll,byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client) { - this.rfHealth = rfHealth; + this.roll = roll; + this.target_system = target_system; + this.target_component = target_component; + this.gimbal_id = gimbal_id; + this.client = client; } /// packet xml order - public static mavlink_uavionix_adsb_transceiver_health_report_t PopulateXMLOrder(/*UAVIONIX_ADSB_RF_HEALTH*/byte rfHealth) + public static mavlink_storm32_gimbal_manager_correct_roll_t PopulateXMLOrder(byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client,float roll) { - var msg = new mavlink_uavionix_adsb_transceiver_health_report_t(); + var msg = new mavlink_storm32_gimbal_manager_correct_roll_t(); - msg.rfHealth = rfHealth; + msg.target_system = target_system; + msg.target_component = target_component; + msg.gimbal_id = gimbal_id; + msg.client = client; + msg.roll = roll; return msg; } - /// ADS-B transponder messages UAVIONIX_ADSB_RF_HEALTH bitmask - [Units("")] - [Description("ADS-B transponder messages")] + /// Roll angle (positive to roll to the right). [rad] + [Units("[rad]")] + [Description("Roll angle (positive to roll to the right).")] //[FieldOffset(0)] - public /*UAVIONIX_ADSB_RF_HEALTH*/byte rfHealth; - }; + public float roll; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Aircraft Registration. - public struct mavlink_uavionix_adsb_out_cfg_registration_t - { - /// packet ordered constructor - public mavlink_uavionix_adsb_out_cfg_registration_t(byte[] registration) - { - this.registration = registration; - - } - - /// packet xml order - public static mavlink_uavionix_adsb_out_cfg_registration_t PopulateXMLOrder(byte[] registration) - { - var msg = new mavlink_uavionix_adsb_out_cfg_registration_t(); + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(4)] + public byte target_system; - msg.registration = registration; - - return msg; - } - + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(5)] + public byte target_component; - /// Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. 'N8644B '. Trailing spaces (0x20) only. This is null-terminated. + /// Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). [Units("")] - [Description("Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. 'N8644B '. Trailing spaces (0x20) only. This is null-terminated.")] - //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] - public byte[] registration; + [Description("Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).")] + //[FieldOffset(6)] + public byte gimbal_id; + + /// Client which is contacting the gimbal manager (must be set). MAV_STORM32_GIMBAL_MANAGER_CLIENT + [Units("")] + [Description("Client which is contacting the gimbal manager (must be set).")] + //[FieldOffset(7)] + public /*MAV_STORM32_GIMBAL_MANAGER_CLIENT*/byte client; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - /// Flight Identification for ADSB-Out vehicles. - public struct mavlink_uavionix_adsb_out_cfg_flightid_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] + /// Message to set a gimbal manager profile. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + public struct mavlink_storm32_gimbal_manager_profile_t { /// packet ordered constructor - public mavlink_uavionix_adsb_out_cfg_flightid_t(byte[] flight_id) + public mavlink_storm32_gimbal_manager_profile_t(byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_PROFILE*/byte profile,byte[] priorities,byte profile_flags,byte rc_timeout,byte[] timeouts) { - this.flight_id = flight_id; + this.target_system = target_system; + this.target_component = target_component; + this.gimbal_id = gimbal_id; + this.profile = profile; + this.priorities = priorities; + this.profile_flags = profile_flags; + this.rc_timeout = rc_timeout; + this.timeouts = timeouts; } /// packet xml order - public static mavlink_uavionix_adsb_out_cfg_flightid_t PopulateXMLOrder(byte[] flight_id) + public static mavlink_storm32_gimbal_manager_profile_t PopulateXMLOrder(byte target_system,byte target_component,byte gimbal_id,/*MAV_STORM32_GIMBAL_MANAGER_PROFILE*/byte profile,byte[] priorities,byte profile_flags,byte rc_timeout,byte[] timeouts) { - var msg = new mavlink_uavionix_adsb_out_cfg_flightid_t(); + var msg = new mavlink_storm32_gimbal_manager_profile_t(); - msg.flight_id = flight_id; + msg.target_system = target_system; + msg.target_component = target_component; + msg.gimbal_id = gimbal_id; + msg.profile = profile; + msg.priorities = priorities; + msg.profile_flags = profile_flags; + msg.rc_timeout = rc_timeout; + msg.timeouts = timeouts; return msg; } - /// Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated. + /// System ID [Units("")] - [Description("Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.")] + [Description("System ID")] //[FieldOffset(0)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=9)] - public byte[] flight_id; - }; + public byte target_system; - - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - /// Request messages. - public struct mavlink_uavionix_adsb_get_t - { - /// packet ordered constructor - public mavlink_uavionix_adsb_get_t(uint ReqMessageId) - { - this.ReqMessageId = ReqMessageId; - - } - - /// packet xml order - public static mavlink_uavionix_adsb_get_t PopulateXMLOrder(uint ReqMessageId) - { - var msg = new mavlink_uavionix_adsb_get_t(); + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(1)] + public byte target_component; - msg.ReqMessageId = ReqMessageId; - - return msg; - } - + /// Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + [Units("")] + [Description("Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).")] + //[FieldOffset(2)] + public byte gimbal_id; - /// Message ID to request. Supports any message in this 10000-10099 range + /// Profile to be applied (0 = default). MAV_STORM32_GIMBAL_MANAGER_PROFILE [Units("")] - [Description("Message ID to request. Supports any message in this 10000-10099 range")] - //[FieldOffset(0)] - public uint ReqMessageId; + [Description("Profile to be applied (0 = default).")] + //[FieldOffset(3)] + public /*MAV_STORM32_GIMBAL_MANAGER_PROFILE*/byte profile; + + /// Priorities for custom profile. + [Units("")] + [Description("Priorities for custom profile.")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] priorities; + + /// Profile flags for custom profile (0 = default). + [Units("")] + [Description("Profile flags for custom profile (0 = default).")] + //[FieldOffset(12)] + public byte profile_flags; + + /// Rc timeouts for custom profile (0 = infinite, in uints of 100 ms). + [Units("")] + [Description("Rc timeouts for custom profile (0 = infinite, in uints of 100 ms).")] + //[FieldOffset(13)] + public byte rc_timeout; + + /// Timeouts for custom profile (0 = infinite, in uints of 100 ms). + [Units("")] + [Description("Timeouts for custom profile (0 = infinite, in uints of 100 ms).")] + //[FieldOffset(14)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] + public byte[] timeouts; }; - + [Obsolete] /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] - /// Control message with all data sent in UCP control message. - public struct mavlink_uavionix_adsb_out_control_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] + /// Information about the shot operation. + public struct mavlink_qshot_status_t { /// packet ordered constructor - public mavlink_uavionix_adsb_out_control_t(int baroAltMSL,ushort squawk,/*UAVIONIX_ADSB_OUT_CONTROL_STATE*/byte state,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus,byte[] flight_id,/*UAVIONIX_ADSB_XBIT*/byte x_bit) + public mavlink_qshot_status_t(/*MAV_QSHOT_MODE*/ushort mode,ushort shot_state) { - this.baroAltMSL = baroAltMSL; - this.squawk = squawk; - this.state = state; - this.emergencyStatus = emergencyStatus; - this.flight_id = flight_id; - this.x_bit = x_bit; + this.mode = mode; + this.shot_state = shot_state; } /// packet xml order - public static mavlink_uavionix_adsb_out_control_t PopulateXMLOrder(/*UAVIONIX_ADSB_OUT_CONTROL_STATE*/byte state,int baroAltMSL,ushort squawk,/*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus,byte[] flight_id,/*UAVIONIX_ADSB_XBIT*/byte x_bit) + public static mavlink_qshot_status_t PopulateXMLOrder(/*MAV_QSHOT_MODE*/ushort mode,ushort shot_state) { - var msg = new mavlink_uavionix_adsb_out_control_t(); + var msg = new mavlink_qshot_status_t(); - msg.state = state; - msg.baroAltMSL = baroAltMSL; - msg.squawk = squawk; - msg.emergencyStatus = emergencyStatus; - msg.flight_id = flight_id; - msg.x_bit = x_bit; + msg.mode = mode; + msg.shot_state = shot_state; return msg; } - /// Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX [mbar] - [Units("[mbar]")] - [Description("Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX")] - //[FieldOffset(0)] - public int baroAltMSL; - - /// Mode A code (typically 1200 [0x04B0] for VFR) - [Units("")] - [Description("Mode A code (typically 1200 [0x04B0] for VFR)")] - //[FieldOffset(4)] - public ushort squawk; - - /// ADS-B transponder control state flags UAVIONIX_ADSB_OUT_CONTROL_STATE bitmask - [Units("")] - [Description("ADS-B transponder control state flags")] - //[FieldOffset(6)] - public /*UAVIONIX_ADSB_OUT_CONTROL_STATE*/byte state; - - /// Emergency status UAVIONIX_ADSB_EMERGENCY_STATUS - [Units("")] - [Description("Emergency status")] - //[FieldOffset(7)] - public /*UAVIONIX_ADSB_EMERGENCY_STATUS*/byte emergencyStatus; - - /// Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. + /// Current shot mode. MAV_QSHOT_MODE [Units("")] - [Description("Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.")] - //[FieldOffset(8)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public byte[] flight_id; + [Description("Current shot mode.")] + //[FieldOffset(0)] + public /*MAV_QSHOT_MODE*/ushort mode; - /// X-Bit enable (military transponders only) UAVIONIX_ADSB_XBIT bitmask + /// Current state in the shot. States are specific to the selected shot mode. [Units("")] - [Description("X-Bit enable (military transponders only)")] - //[FieldOffset(16)] - public /*UAVIONIX_ADSB_XBIT*/byte x_bit; + [Description("Current state in the shot. States are specific to the selected shot mode.")] + //[FieldOffset(2)] + public ushort shot_state; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - /// Status message with information from UCP Heartbeat and Status messages. - public struct mavlink_uavionix_adsb_out_status_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=10)] + /// Message reporting the status of the prearm checks. The flags are component specific. + public struct mavlink_component_prearm_status_t { /// packet ordered constructor - public mavlink_uavionix_adsb_out_status_t(ushort squawk,/*UAVIONIX_ADSB_OUT_STATUS_STATE*/byte state,/*UAVIONIX_ADSB_OUT_STATUS_NIC_NACP*/byte NIC_NACp,byte boardTemp,/*UAVIONIX_ADSB_OUT_STATUS_FAULT*/byte fault,byte[] flight_id) + public mavlink_component_prearm_status_t(uint enabled_flags,uint fail_flags,byte target_system,byte target_component) { - this.squawk = squawk; - this.state = state; - this.NIC_NACp = NIC_NACp; - this.boardTemp = boardTemp; - this.fault = fault; - this.flight_id = flight_id; + this.enabled_flags = enabled_flags; + this.fail_flags = fail_flags; + this.target_system = target_system; + this.target_component = target_component; } /// packet xml order - public static mavlink_uavionix_adsb_out_status_t PopulateXMLOrder(/*UAVIONIX_ADSB_OUT_STATUS_STATE*/byte state,ushort squawk,/*UAVIONIX_ADSB_OUT_STATUS_NIC_NACP*/byte NIC_NACp,byte boardTemp,/*UAVIONIX_ADSB_OUT_STATUS_FAULT*/byte fault,byte[] flight_id) + public static mavlink_component_prearm_status_t PopulateXMLOrder(byte target_system,byte target_component,uint enabled_flags,uint fail_flags) { - var msg = new mavlink_uavionix_adsb_out_status_t(); + var msg = new mavlink_component_prearm_status_t(); - msg.state = state; - msg.squawk = squawk; - msg.NIC_NACp = NIC_NACp; - msg.boardTemp = boardTemp; - msg.fault = fault; - msg.flight_id = flight_id; + msg.target_system = target_system; + msg.target_component = target_component; + msg.enabled_flags = enabled_flags; + msg.fail_flags = fail_flags; return msg; } - /// Mode A code (typically 1200 [0x04B0] for VFR) + /// Currently enabled prearm checks. 0 means no checks are being performed, UINT32_MAX means not known. [Units("")] - [Description("Mode A code (typically 1200 [0x04B0] for VFR)")] + [Description("Currently enabled prearm checks. 0 means no checks are being performed, UINT32_MAX means not known.")] //[FieldOffset(0)] - public ushort squawk; + public uint enabled_flags; - /// ADS-B transponder status state flags UAVIONIX_ADSB_OUT_STATUS_STATE bitmask - [Units("")] - [Description("ADS-B transponder status state flags")] - //[FieldOffset(2)] - public /*UAVIONIX_ADSB_OUT_STATUS_STATE*/byte state; - - /// Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively UAVIONIX_ADSB_OUT_STATUS_NIC_NACP - [Units("")] - [Description("Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively")] - //[FieldOffset(3)] - public /*UAVIONIX_ADSB_OUT_STATUS_NIC_NACP*/byte NIC_NACp; - - /// Board temperature in C + /// Currently not passed prearm checks. 0 means all checks have been passed. [Units("")] - [Description("Board temperature in C")] + [Description("Currently not passed prearm checks. 0 means all checks have been passed.")] //[FieldOffset(4)] - public byte boardTemp; + public uint fail_flags; - /// ADS-B transponder fault flags UAVIONIX_ADSB_OUT_STATUS_FAULT bitmask + /// System ID [Units("")] - [Description("ADS-B transponder fault flags")] - //[FieldOffset(5)] - public /*UAVIONIX_ADSB_OUT_STATUS_FAULT*/byte fault; + [Description("System ID")] + //[FieldOffset(8)] + public byte target_system; - /// Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. + /// Component ID [Units("")] - [Description("Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.")] - //[FieldOffset(6)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=8)] - public byte[] flight_id; + [Description("Component ID")] + //[FieldOffset(9)] + public byte target_component; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] - /// ICAROUS heartbeat - public struct mavlink_icarous_heartbeat_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] + /// AVSS PRS system status. + public struct mavlink_avss_prs_sys_status_t { /// packet ordered constructor - public mavlink_icarous_heartbeat_t(/*ICAROUS_FMS_STATE*/byte status) + public mavlink_avss_prs_sys_status_t(uint time_boot_ms,uint error_status,uint battery_status,byte arm_status,byte charge_status) { - this.status = status; + this.time_boot_ms = time_boot_ms; + this.error_status = error_status; + this.battery_status = battery_status; + this.arm_status = arm_status; + this.charge_status = charge_status; } /// packet xml order - public static mavlink_icarous_heartbeat_t PopulateXMLOrder(/*ICAROUS_FMS_STATE*/byte status) + public static mavlink_avss_prs_sys_status_t PopulateXMLOrder(uint time_boot_ms,uint error_status,uint battery_status,byte arm_status,byte charge_status) { - var msg = new mavlink_icarous_heartbeat_t(); + var msg = new mavlink_avss_prs_sys_status_t(); - msg.status = status; + msg.time_boot_ms = time_boot_ms; + msg.error_status = error_status; + msg.battery_status = battery_status; + msg.arm_status = arm_status; + msg.charge_status = charge_status; return msg; } - /// See the FMS_STATE enum. ICAROUS_FMS_STATE - [Units("")] - [Description("See the FMS_STATE enum.")] + /// Timestamp (time since PRS boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since PRS boot).")] //[FieldOffset(0)] - public /*ICAROUS_FMS_STATE*/byte status; + public uint time_boot_ms; + + /// PRS error statuses + [Units("")] + [Description("PRS error statuses")] + //[FieldOffset(4)] + public uint error_status; + + /// Estimated battery run-time without a remote connection and PRS battery voltage + [Units("")] + [Description("Estimated battery run-time without a remote connection and PRS battery voltage")] + //[FieldOffset(8)] + public uint battery_status; + + /// PRS arm statuses + [Units("")] + [Description("PRS arm statuses")] + //[FieldOffset(12)] + public byte arm_status; + + /// PRS battery charge statuses + [Units("")] + [Description("PRS battery charge statuses")] + //[FieldOffset(13)] + public byte charge_status; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] - /// Kinematic multi bands (track) output from Daidalus - public struct mavlink_icarous_kinematic_bands_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)] + /// Drone position. + public struct mavlink_avss_drone_position_t { /// packet ordered constructor - public mavlink_icarous_kinematic_bands_t(float min1,float max1,float min2,float max2,float min3,float max3,float min4,float max4,float min5,float max5,sbyte numBands,/*ICAROUS_TRACK_BAND_TYPES*/byte type1,/*ICAROUS_TRACK_BAND_TYPES*/byte type2,/*ICAROUS_TRACK_BAND_TYPES*/byte type3,/*ICAROUS_TRACK_BAND_TYPES*/byte type4,/*ICAROUS_TRACK_BAND_TYPES*/byte type5) + public mavlink_avss_drone_position_t(uint time_boot_ms,int lat,int lon,int alt,float ground_alt,float barometer_alt) { - this.min1 = min1; - this.max1 = max1; - this.min2 = min2; - this.max2 = max2; - this.min3 = min3; - this.max3 = max3; - this.min4 = min4; - this.max4 = max4; - this.min5 = min5; - this.max5 = max5; - this.numBands = numBands; - this.type1 = type1; - this.type2 = type2; - this.type3 = type3; - this.type4 = type4; - this.type5 = type5; + this.time_boot_ms = time_boot_ms; + this.lat = lat; + this.lon = lon; + this.alt = alt; + this.ground_alt = ground_alt; + this.barometer_alt = barometer_alt; } /// packet xml order - public static mavlink_icarous_kinematic_bands_t PopulateXMLOrder(sbyte numBands,/*ICAROUS_TRACK_BAND_TYPES*/byte type1,float min1,float max1,/*ICAROUS_TRACK_BAND_TYPES*/byte type2,float min2,float max2,/*ICAROUS_TRACK_BAND_TYPES*/byte type3,float min3,float max3,/*ICAROUS_TRACK_BAND_TYPES*/byte type4,float min4,float max4,/*ICAROUS_TRACK_BAND_TYPES*/byte type5,float min5,float max5) + public static mavlink_avss_drone_position_t PopulateXMLOrder(uint time_boot_ms,int lat,int lon,int alt,float ground_alt,float barometer_alt) { - var msg = new mavlink_icarous_kinematic_bands_t(); + var msg = new mavlink_avss_drone_position_t(); - msg.numBands = numBands; - msg.type1 = type1; - msg.min1 = min1; - msg.max1 = max1; - msg.type2 = type2; - msg.min2 = min2; - msg.max2 = max2; - msg.type3 = type3; - msg.min3 = min3; - msg.max3 = max3; - msg.type4 = type4; - msg.min4 = min4; - msg.max4 = max4; - msg.type5 = type5; - msg.min5 = min5; - msg.max5 = max5; + msg.time_boot_ms = time_boot_ms; + msg.lat = lat; + msg.lon = lon; + msg.alt = alt; + msg.ground_alt = ground_alt; + msg.barometer_alt = barometer_alt; return msg; } - /// min angle (degrees) [deg] - [Units("[deg]")] - [Description("min angle (degrees)")] + /// Timestamp (time since FC boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since FC boot).")] //[FieldOffset(0)] - public float min1; + public uint time_boot_ms; - /// max angle (degrees) [deg] - [Units("[deg]")] - [Description("max angle (degrees)")] + /// Latitude, expressed [degE7] + [Units("[degE7]")] + [Description("Latitude, expressed")] //[FieldOffset(4)] - public float max1; + public int lat; - /// min angle (degrees) [deg] - [Units("[deg]")] - [Description("min angle (degrees)")] + /// Longitude, expressed [degE7] + [Units("[degE7]")] + [Description("Longitude, expressed")] //[FieldOffset(8)] - public float min2; + public int lon; - /// max angle (degrees) [deg] - [Units("[deg]")] - [Description("max angle (degrees)")] + /// Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. [mm] + [Units("[mm]")] + [Description("Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.")] //[FieldOffset(12)] - public float max2; + public int alt; - /// min angle (degrees) [deg] - [Units("[deg]")] - [Description("min angle (degrees)")] + /// Altitude above ground, This altitude is measured by a ultrasound, Laser rangefinder or millimeter-wave radar [m] + [Units("[m]")] + [Description("Altitude above ground, This altitude is measured by a ultrasound, Laser rangefinder or millimeter-wave radar")] //[FieldOffset(16)] - public float min3; + public float ground_alt; - /// max angle (degrees) [deg] - [Units("[deg]")] - [Description("max angle (degrees)")] + /// This altitude is measured by a barometer [m] + [Units("[m]")] + [Description("This altitude is measured by a barometer")] //[FieldOffset(20)] - public float max3; - - /// min angle (degrees) [deg] - [Units("[deg]")] - [Description("min angle (degrees)")] - //[FieldOffset(24)] - public float min4; - - /// max angle (degrees) [deg] - [Units("[deg]")] - [Description("max angle (degrees)")] - //[FieldOffset(28)] - public float max4; - - /// min angle (degrees) [deg] - [Units("[deg]")] - [Description("min angle (degrees)")] - //[FieldOffset(32)] - public float min5; - - /// max angle (degrees) [deg] - [Units("[deg]")] - [Description("max angle (degrees)")] - //[FieldOffset(36)] - public float max5; - - /// Number of track bands - [Units("")] - [Description("Number of track bands")] - //[FieldOffset(40)] - public sbyte numBands; - - /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES - [Units("")] - [Description("See the TRACK_BAND_TYPES enum.")] - //[FieldOffset(41)] - public /*ICAROUS_TRACK_BAND_TYPES*/byte type1; - - /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES - [Units("")] - [Description("See the TRACK_BAND_TYPES enum.")] - //[FieldOffset(42)] - public /*ICAROUS_TRACK_BAND_TYPES*/byte type2; - - /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES - [Units("")] - [Description("See the TRACK_BAND_TYPES enum.")] - //[FieldOffset(43)] - public /*ICAROUS_TRACK_BAND_TYPES*/byte type3; - - /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES - [Units("")] - [Description("See the TRACK_BAND_TYPES enum.")] - //[FieldOffset(44)] - public /*ICAROUS_TRACK_BAND_TYPES*/byte type4; - - /// See the TRACK_BAND_TYPES enum. ICAROUS_TRACK_BAND_TYPES - [Units("")] - [Description("See the TRACK_BAND_TYPES enum.")] - //[FieldOffset(45)] - public /*ICAROUS_TRACK_BAND_TYPES*/byte type5; + public float barometer_alt; }; /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=85)] - /// Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit. - public struct mavlink_loweheiser_gov_efi_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] + /// Drone IMU data. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + public struct mavlink_avss_drone_imu_t { /// packet ordered constructor - public mavlink_loweheiser_gov_efi_t(float volt_batt,float curr_batt,float curr_gen,float curr_rot,float fuel_level,float throttle,uint runtime,int until_maintenance,float rectifier_temp,float generator_temp,float efi_batt,float efi_rpm,float efi_pw,float efi_fuel_flow,float efi_fuel_consumed,float efi_baro,float efi_mat,float efi_clt,float efi_tps,float efi_exhaust_gas_temperature,ushort generator_status,ushort efi_status,byte efi_index) + public mavlink_avss_drone_imu_t(uint time_boot_ms,float q1,float q2,float q3,float q4,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro) { - this.volt_batt = volt_batt; - this.curr_batt = curr_batt; - this.curr_gen = curr_gen; - this.curr_rot = curr_rot; - this.fuel_level = fuel_level; - this.throttle = throttle; - this.runtime = runtime; - this.until_maintenance = until_maintenance; - this.rectifier_temp = rectifier_temp; - this.generator_temp = generator_temp; - this.efi_batt = efi_batt; - this.efi_rpm = efi_rpm; - this.efi_pw = efi_pw; - this.efi_fuel_flow = efi_fuel_flow; - this.efi_fuel_consumed = efi_fuel_consumed; - this.efi_baro = efi_baro; - this.efi_mat = efi_mat; - this.efi_clt = efi_clt; - this.efi_tps = efi_tps; - this.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature; - this.generator_status = generator_status; - this.efi_status = efi_status; - this.efi_index = efi_index; + this.time_boot_ms = time_boot_ms; + this.q1 = q1; + this.q2 = q2; + this.q3 = q3; + this.q4 = q4; + this.xacc = xacc; + this.yacc = yacc; + this.zacc = zacc; + this.xgyro = xgyro; + this.ygyro = ygyro; + this.zgyro = zgyro; } /// packet xml order - public static mavlink_loweheiser_gov_efi_t PopulateXMLOrder(float volt_batt,float curr_batt,float curr_gen,float curr_rot,float fuel_level,float throttle,uint runtime,int until_maintenance,float rectifier_temp,float generator_temp,float efi_batt,float efi_rpm,float efi_pw,float efi_fuel_flow,float efi_fuel_consumed,float efi_baro,float efi_mat,float efi_clt,float efi_tps,float efi_exhaust_gas_temperature,byte efi_index,ushort generator_status,ushort efi_status) + public static mavlink_avss_drone_imu_t PopulateXMLOrder(uint time_boot_ms,float q1,float q2,float q3,float q4,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro) { - var msg = new mavlink_loweheiser_gov_efi_t(); + var msg = new mavlink_avss_drone_imu_t(); - msg.volt_batt = volt_batt; - msg.curr_batt = curr_batt; - msg.curr_gen = curr_gen; - msg.curr_rot = curr_rot; - msg.fuel_level = fuel_level; - msg.throttle = throttle; - msg.runtime = runtime; - msg.until_maintenance = until_maintenance; - msg.rectifier_temp = rectifier_temp; - msg.generator_temp = generator_temp; - msg.efi_batt = efi_batt; - msg.efi_rpm = efi_rpm; - msg.efi_pw = efi_pw; - msg.efi_fuel_flow = efi_fuel_flow; - msg.efi_fuel_consumed = efi_fuel_consumed; - msg.efi_baro = efi_baro; - msg.efi_mat = efi_mat; - msg.efi_clt = efi_clt; - msg.efi_tps = efi_tps; - msg.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature; - msg.efi_index = efi_index; - msg.generator_status = generator_status; - msg.efi_status = efi_status; + msg.time_boot_ms = time_boot_ms; + msg.q1 = q1; + msg.q2 = q2; + msg.q3 = q3; + msg.q4 = q4; + msg.xacc = xacc; + msg.yacc = yacc; + msg.zacc = zacc; + msg.xgyro = xgyro; + msg.ygyro = ygyro; + msg.zgyro = zgyro; return msg; } - /// Generator Battery voltage. [V] - [Units("[V]")] - [Description("Generator Battery voltage.")] + /// Timestamp (time since FC boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since FC boot).")] //[FieldOffset(0)] - public float volt_batt; + public uint time_boot_ms; - /// Generator Battery current. [A] - [Units("[A]")] - [Description("Generator Battery current.")] + /// Quaternion component 1, w (1 in null-rotation) + [Units("")] + [Description("Quaternion component 1, w (1 in null-rotation)")] //[FieldOffset(4)] - public float curr_batt; + public float q1; - /// Current being produced by generator. [A] - [Units("[A]")] - [Description("Current being produced by generator.")] + /// Quaternion component 2, x (0 in null-rotation) + [Units("")] + [Description("Quaternion component 2, x (0 in null-rotation)")] //[FieldOffset(8)] - public float curr_gen; + public float q2; - /// Load current being consumed by the UAV (sum of curr_gen and curr_batt) [A] - [Units("[A]")] - [Description("Load current being consumed by the UAV (sum of curr_gen and curr_batt)")] + /// Quaternion component 3, y (0 in null-rotation) + [Units("")] + [Description("Quaternion component 3, y (0 in null-rotation)")] //[FieldOffset(12)] - public float curr_rot; + public float q3; - /// Generator fuel remaining in litres. [l] - [Units("[l]")] - [Description("Generator fuel remaining in litres.")] + /// Quaternion component 4, z (0 in null-rotation) + [Units("")] + [Description("Quaternion component 4, z (0 in null-rotation)")] //[FieldOffset(16)] - public float fuel_level; + public float q4; - /// Throttle Output. [%] - [Units("[%]")] - [Description("Throttle Output.")] + /// X acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("X acceleration")] //[FieldOffset(20)] - public float throttle; + public float xacc; - /// Seconds this generator has run since it was rebooted. [s] - [Units("[s]")] - [Description("Seconds this generator has run since it was rebooted.")] + /// Y acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Y acceleration")] //[FieldOffset(24)] - public uint runtime; + public float yacc; - /// Seconds until this generator requires maintenance. A negative value indicates maintenance is past due. [s] - [Units("[s]")] - [Description("Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.")] + /// Z acceleration [m/s/s] + [Units("[m/s/s]")] + [Description("Z acceleration")] //[FieldOffset(28)] - public int until_maintenance; + public float zacc; - /// The Temperature of the rectifier. [degC] - [Units("[degC]")] - [Description("The Temperature of the rectifier.")] + /// Angular speed around X axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around X axis")] //[FieldOffset(32)] - public float rectifier_temp; + public float xgyro; - /// The temperature of the mechanical motor, fuel cell core or generator. [degC] - [Units("[degC]")] - [Description("The temperature of the mechanical motor, fuel cell core or generator.")] + /// Angular speed around Y axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Y axis")] //[FieldOffset(36)] - public float generator_temp; + public float ygyro; - /// EFI Supply Voltage. [V] - [Units("[V]")] - [Description(" EFI Supply Voltage.")] + /// Angular speed around Z axis [rad/s] + [Units("[rad/s]")] + [Description("Angular speed around Z axis")] //[FieldOffset(40)] - public float efi_batt; - - /// Motor RPM. [rpm] - [Units("[rpm]")] - [Description("Motor RPM.")] - //[FieldOffset(44)] - public float efi_rpm; - - /// Injector pulse-width in miliseconds. [ms] - [Units("[ms]")] - [Description("Injector pulse-width in miliseconds.")] - //[FieldOffset(48)] - public float efi_pw; - - /// Fuel flow rate in litres/hour. - [Units("")] - [Description("Fuel flow rate in litres/hour.")] - //[FieldOffset(52)] - public float efi_fuel_flow; - - /// Fuel consumed. [l] - [Units("[l]")] - [Description("Fuel consumed.")] - //[FieldOffset(56)] - public float efi_fuel_consumed; - - /// Atmospheric pressure. [kPa] - [Units("[kPa]")] - [Description("Atmospheric pressure.")] - //[FieldOffset(60)] - public float efi_baro; - - /// Manifold Air Temperature. [degC] - [Units("[degC]")] - [Description("Manifold Air Temperature.")] - //[FieldOffset(64)] - public float efi_mat; - - /// Cylinder Head Temperature. [degC] - [Units("[degC]")] - [Description("Cylinder Head Temperature.")] - //[FieldOffset(68)] - public float efi_clt; + public float zgyro; + }; - /// Throttle Position. [%] - [Units("[%]")] - [Description("Throttle Position.")] - //[FieldOffset(72)] - public float efi_tps; + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] + /// Drone operation mode. + public struct mavlink_avss_drone_operation_mode_t + { + /// packet ordered constructor + public mavlink_avss_drone_operation_mode_t(uint time_boot_ms,byte M300_operation_mode,byte horsefly_operation_mode) + { + this.time_boot_ms = time_boot_ms; + this.M300_operation_mode = M300_operation_mode; + this.horsefly_operation_mode = horsefly_operation_mode; + + } + + /// packet xml order + public static mavlink_avss_drone_operation_mode_t PopulateXMLOrder(uint time_boot_ms,byte M300_operation_mode,byte horsefly_operation_mode) + { + var msg = new mavlink_avss_drone_operation_mode_t(); - /// Exhaust gas temperature. [degC] - [Units("[degC]")] - [Description("Exhaust gas temperature.")] - //[FieldOffset(76)] - public float efi_exhaust_gas_temperature; + msg.time_boot_ms = time_boot_ms; + msg.M300_operation_mode = M300_operation_mode; + msg.horsefly_operation_mode = horsefly_operation_mode; + + return msg; + } + - /// Generator status. - [Units("")] - [Description("Generator status.")] - //[FieldOffset(80)] - public ushort generator_status; + /// Timestamp (time since FC boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since FC boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; - /// EFI status. + /// DJI M300 operation mode [Units("")] - [Description("EFI status.")] - //[FieldOffset(82)] - public ushort efi_status; + [Description("DJI M300 operation mode")] + //[FieldOffset(4)] + public byte M300_operation_mode; - /// EFI index. + /// horsefly operation mode [Units("")] - [Description("EFI index.")] - //[FieldOffset(84)] - public byte efi_index; + [Description("horsefly operation mode")] + //[FieldOffset(5)] + public byte horsefly_operation_mode; }; @@ -31816,75 +37325,4 @@ public static mavlink_airlink_auth_response_t PopulateXMLOrder(/*AIRLINK_AUTH_RE 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 - public struct mavlink_heartbeat_t - { - /// packet ordered constructor - public mavlink_heartbeat_t(uint custom_mode,/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,/*MAV_MODE_FLAG*/byte base_mode,/*MAV_STATE*/byte system_status,byte mavlink_version) - { - this.custom_mode = custom_mode; - this.type = type; - this.autopilot = autopilot; - this.base_mode = base_mode; - this.system_status = system_status; - this.mavlink_version = mavlink_version; - - } - - /// packet xml order - public static mavlink_heartbeat_t PopulateXMLOrder(/*MAV_TYPE*/byte type,/*MAV_AUTOPILOT*/byte autopilot,/*MAV_MODE_FLAG*/byte base_mode,uint custom_mode,/*MAV_STATE*/byte system_status,byte mavlink_version) - { - var msg = new mavlink_heartbeat_t(); - - msg.type = type; - msg.autopilot = autopilot; - msg.base_mode = base_mode; - msg.custom_mode = custom_mode; - msg.system_status = system_status; - msg.mavlink_version = mavlink_version; - - return msg; - } - - - /// A bitfield for use for autopilot-specific flags - [Units("")] - [Description("A bitfield for use for autopilot-specific flags")] - //[FieldOffset(0)] - public uint custom_mode; - - /// Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. MAV_TYPE - [Units("")] - [Description("Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.")] - //[FieldOffset(4)] - public /*MAV_TYPE*/byte type; - - /// Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. MAV_AUTOPILOT - [Units("")] - [Description("Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.")] - //[FieldOffset(5)] - public /*MAV_AUTOPILOT*/byte autopilot; - - /// System mode bitmap. MAV_MODE_FLAG bitmask - [Units("")] - [Description("System mode bitmap.")] - //[FieldOffset(6)] - public /*MAV_MODE_FLAG*/byte base_mode; - - /// System status flag. MAV_STATE - [Units("")] - [Description("System status flag.")] - //[FieldOffset(7)] - public /*MAV_STATE*/byte system_status; - - /// MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - [Units("")] - [Description("MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version")] - //[FieldOffset(8)] - public byte mavlink_version; - }; - } diff --git a/ExtLibs/Mavlink/mavlink.lua b/ExtLibs/Mavlink/mavlink.lua index c7522d15af..bb360af0ce 100644 --- a/ExtLibs/Mavlink/mavlink.lua +++ b/ExtLibs/Mavlink/mavlink.lua @@ -20,6 +20,7 @@ protocolVersions = { } messageName = { + [26900] = 'zVIDEO_STREAM_INFORMATION', [150] = 'SENSOR_OFFSETS', [151] = 'SET_MAG_OFFSETS', [152] = 'MEMINFO', @@ -92,7 +93,23 @@ messageName = { [11042] = 'ESC_TELEMETRY_21_TO_24', [11043] = 'ESC_TELEMETRY_25_TO_28', [11044] = 'ESC_TELEMETRY_29_TO_32', - [26900] = 'VIDEO_STREAM_INFORMATION99', + [223] = 'COMMAND_INT_STAMPED', + [224] = 'COMMAND_LONG_STAMPED', + [8002] = 'SENS_POWER', + [8003] = 'SENS_MPPT', + [8004] = 'ASLCTRL_DATA', + [8005] = 'ASLCTRL_DEBUG', + [8006] = 'ASLUAV_STATUS', + [8007] = 'EKF_EXT', + [8008] = 'ASL_OBCTRL', + [8009] = 'SENS_ATMOS', + [8010] = 'SENS_BATMON', + [8011] = 'FW_SOARING_DATA', + [8012] = 'SENSORPOD_STATUS', + [8013] = 'SENS_POWER_BOARD', + [8014] = 'GSM_LINK_STATUS', + [8015] = 'SATCOM_LINK_STATUS', + [8016] = 'SENSOR_AIRFLOW_ANGLES', [1] = 'SYS_STATUS', [2] = 'SYSTEM_TIME', [4] = 'PING', @@ -271,6 +288,8 @@ messageName = { [324] = 'PARAM_EXT_ACK', [330] = 'OBSTACLE_DISTANCE', [331] = 'ODOMETRY', + [332] = 'TRAJECTORY_REPRESENTATION_WAYPOINTS', + [333] = 'TRAJECTORY_REPRESENTATION_BEZIER', [335] = 'ISBD_LINK_STATUS', [339] = 'RAW_RPM', [340] = 'UTM_GLOBAL_POSITION', @@ -295,6 +314,28 @@ messageName = { [12915] = 'OPEN_DRONE_ID_MESSAGE_PACK', [12919] = 'OPEN_DRONE_ID_SYSTEM_UPDATE', [12920] = 'HYGROMETER_SENSOR', + [53] = 'MISSION_CHECKSUM', + [295] = 'AIRSPEED', + [420] = 'RADIO_RC_CHANNELS', + [435] = 'AVAILABLE_MODES', + [436] = 'CURRENT_MODE', + [437] = 'AVAILABLE_MODES_MONITOR', + [441] = 'GNSS_INTEGRITY', + [42000] = 'ICAROUS_HEARTBEAT', + [42001] = 'ICAROUS_KINEMATIC_BANDS', + [0] = 'HEARTBEAT', + [17150] = 'ARRAY_TEST_0', + [17151] = 'ARRAY_TEST_1', + [17153] = 'ARRAY_TEST_3', + [17154] = 'ARRAY_TEST_4', + [17155] = 'ARRAY_TEST_5', + [17156] = 'ARRAY_TEST_6', + [17157] = 'ARRAY_TEST_7', + [17158] = 'ARRAY_TEST_8', + [17000] = 'TEST_TYPES', + [220] = 'NAV_FILTER_BIAS', + [221] = 'RADIO_CALIBRATION', + [222] = 'UALBERTA_SYS_STATUS', [10001] = 'UAVIONIX_ADSB_OUT_CFG', [10002] = 'UAVIONIX_ADSB_OUT_DYNAMIC', [10003] = 'UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT', @@ -303,9 +344,21 @@ messageName = { [10006] = 'UAVIONIX_ADSB_GET', [10007] = 'UAVIONIX_ADSB_OUT_CONTROL', [10008] = 'UAVIONIX_ADSB_OUT_STATUS', - [42000] = 'ICAROUS_HEARTBEAT', - [42001] = 'ICAROUS_KINEMATIC_BANDS', [10151] = 'LOWEHEISER_GOV_EFI', + [60001] = 'STORM32_GIMBAL_DEVICE_STATUS', + [60002] = 'STORM32_GIMBAL_DEVICE_CONTROL', + [60010] = 'STORM32_GIMBAL_MANAGER_INFORMATION', + [60011] = 'STORM32_GIMBAL_MANAGER_STATUS', + [60012] = 'STORM32_GIMBAL_MANAGER_CONTROL', + [60013] = 'STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW', + [60014] = 'STORM32_GIMBAL_MANAGER_CORRECT_ROLL', + [60015] = 'STORM32_GIMBAL_MANAGER_PROFILE', + [60020] = 'QSHOT_STATUS', + [60025] = 'COMPONENT_PREARM_STATUS', + [60050] = 'AVSS_PRS_SYS_STATUS', + [60051] = 'AVSS_DRONE_POSITION', + [60052] = 'AVSS_DRONE_IMU', + [60053] = 'AVSS_DRONE_OPERATION_MODE', [50001] = 'CUBEPILOT_RAW_RC', [50002] = 'HERELINK_VIDEO_STREAM_INFORMATION', [50003] = 'HERELINK_TELEM', @@ -313,7 +366,6 @@ messageName = { [50005] = 'CUBEPILOT_FIRMWARE_UPDATE_RESP', [52000] = 'AIRLINK_AUTH', [52001] = 'AIRLINK_AUTH_RESPONSE', - [0] = 'HEARTBEAT', } local enumEntryName = { @@ -330,6 +382,7 @@ local enumEntryName = { ["HEADING_TYPE"] = { [0] = "HEADING_TYPE_COURSE_OVER_GROUND", [1] = "HEADING_TYPE_HEADING", + [2] = "HEADING_TYPE_DEFAULT", }, ["MAV_CMD"] = { [16] = "MAV_CMD_NAV_WAYPOINT", @@ -415,6 +468,7 @@ local enumEntryName = { [246] = "MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN", [252] = "MAV_CMD_OVERRIDE_GOTO", [260] = "MAV_CMD_OBLIQUE_SURVEY", + [262] = "MAV_CMD_DO_SET_STANDARD_MODE", [300] = "MAV_CMD_MISSION_START", [400] = "MAV_CMD_COMPONENT_ARM_DISARM", [401] = "MAV_CMD_RUN_PREARM_CHECKS", @@ -439,6 +493,7 @@ local enumEntryName = { [534] = "MAV_CMD_SET_CAMERA_SOURCE", [600] = "MAV_CMD_JUMP_TAG", [601] = "MAV_CMD_DO_JUMP_TAG", + [610] = "MAV_CMD_DO_SET_SYS_CMP_ID", [1000] = "MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW", [1001] = "MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE", [2000] = "MAV_CMD_IMAGE_START_CAPTURE", @@ -490,6 +545,8 @@ local enumEntryName = { [31013] = "MAV_CMD_USER_4", [31014] = "MAV_CMD_USER_5", [32000] = "MAV_CMD_CAN_FORWARD", + [40001] = "MAV_CMD_RESET_MPPT", + [40002] = "MAV_CMD_PAYLOAD_CONTROL", [42000] = "MAV_CMD_POWER_OFF_INITIATED", [42001] = "MAV_CMD_SOLO_BTN_FLY_CLICK", [42002] = "MAV_CMD_SOLO_BTN_FLY_HOLD", @@ -519,7 +576,19 @@ local enumEntryName = { [43001] = "MAV_CMD_GUIDED_CHANGE_ALTITUDE", [43002] = "MAV_CMD_GUIDED_CHANGE_HEADING", [43003] = "MAV_CMD_EXTERNAL_POSITION_ESTIMATE", + [43004] = "MAV_CMD_EXTERNAL_WIND_ESTIMATE", [43005] = "MAV_CMD_SET_HAGL", + [60002] = "MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW", + [60010] = "MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP", + [60011] = "MAV_CMD_STORM32_DO_GIMBAL_ACTION", + [60020] = "MAV_CMD_QSHOT_DO_CONFIGURE", + [60050] = "MAV_CMD_PRS_SET_ARM", + [60051] = "MAV_CMD_PRS_GET_ARM", + [60052] = "MAV_CMD_PRS_GET_BATTERY", + [60053] = "MAV_CMD_PRS_GET_ERR", + [60070] = "MAV_CMD_PRS_SET_ARM_ALTI", + [60071] = "MAV_CMD_PRS_GET_ARM_ALTI", + [60072] = "MAV_CMD_PRS_SHUTDOWN", }, ["SCRIPTING_CMD"] = { [0] = "SCRIPTING_CMD_REPL_START", @@ -909,6 +978,17 @@ local enumEntryName = { [2] = "OSD_PARAM_INVALID_PARAMETER_INDEX", [3] = "OSD_PARAM_INVALID_PARAMETER", }, + ["GSM_LINK_TYPE"] = { + [0] = "GSM_LINK_TYPE_NONE", + [1] = "GSM_LINK_TYPE_UNKNOWN", + [2] = "GSM_LINK_TYPE_2G", + [3] = "GSM_LINK_TYPE_3G", + [4] = "GSM_LINK_TYPE_4G", + }, + ["GSM_MODEM_TYPE"] = { + [0] = "GSM_MODEM_TYPE_UNKNOWN", + [1] = "GSM_MODEM_TYPE_HUAWEI_E3372", + }, ["FIRMWARE_VERSION_TYPE"] = { [0] = "FIRMWARE_VERSION_TYPE_DEV", [64] = "FIRMWARE_VERSION_TYPE_ALPHA", @@ -2042,126 +2122,63 @@ local enumEntryName = { [0] = "SAFETY_SWITCH_STATE_SAFE", [1] = "SAFETY_SWITCH_STATE_DANGEROUS", }, - ["UAVIONIX_ADSB_OUT_DYNAMIC_STATE"] = { - [1] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", - [2] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", - [4] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED", - [8] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND", - [16] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT", - }, - ["UAVIONIX_ADSB_OUT_RF_SELECT"] = { - [0] = "UAVIONIX_ADSB_OUT_RF_SELECT_STANDBY", - [1] = "UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED", - [2] = "UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED", + ["AIRSPEED_SENSOR_FLAGS"] = { + [0] = "AIRSPEED_SENSOR_UNHEALTHY", + [1] = "AIRSPEED_SENSOR_USING", }, - ["UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX"] = { - [0] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0", - [1] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1", - [2] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D", - [3] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D", - [4] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS", - [5] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK", + ["RADIO_RC_CHANNELS_FLAGS"] = { + [1] = "RADIO_RC_CHANNELS_FLAGS_FAILSAFE", + [2] = "RADIO_RC_CHANNELS_FLAGS_OUTDATED", }, - ["UAVIONIX_ADSB_RF_HEALTH"] = { - [0] = "UAVIONIX_ADSB_RF_HEALTH_INITIALIZING", - [1] = "UAVIONIX_ADSB_RF_HEALTH_OK", - [2] = "UAVIONIX_ADSB_RF_HEALTH_FAIL_TX", - [16] = "UAVIONIX_ADSB_RF_HEALTH_FAIL_RX", + ["MAV_STANDARD_MODE"] = { + [0] = "MAV_STANDARD_MODE_NON_STANDARD", + [1] = "MAV_STANDARD_MODE_POSITION_HOLD", + [2] = "MAV_STANDARD_MODE_ORBIT", + [3] = "MAV_STANDARD_MODE_CRUISE", + [4] = "MAV_STANDARD_MODE_ALTITUDE_HOLD", + [5] = "MAV_STANDARD_MODE_RETURN_HOME", + [6] = "MAV_STANDARD_MODE_SAFE_RECOVERY", + [7] = "MAV_STANDARD_MODE_MISSION", + [8] = "MAV_STANDARD_MODE_LAND", + [9] = "MAV_STANDARD_MODE_TAKEOFF", }, - ["UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE"] = { - [0] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA", - [1] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M", - [2] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M", - [3] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M", - [4] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M", - [5] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M", - [6] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M", - [7] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M", - [8] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M", - [9] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M", - [10] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M", - [11] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M", - [12] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M", - [13] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M", - [14] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M", - [15] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M", - }, - ["UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT"] = { - [0] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA", - [1] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M", - [2] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M", - [3] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M", - [4] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M", - [5] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M", - [6] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M", - [7] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M", - }, - ["UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON"] = { - [0] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA", - [1] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR", - }, - ["UAVIONIX_ADSB_EMERGENCY_STATUS"] = { - [0] = "UAVIONIX_ADSB_OUT_NO_EMERGENCY", - [1] = "UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY", - [2] = "UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY", - [3] = "UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY", - [4] = "UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY", - [5] = "UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY", - [6] = "UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY", - [7] = "UAVIONIX_ADSB_OUT_RESERVED", + ["MAV_MODE_PROPERTY"] = { + [1] = "MAV_MODE_PROPERTY_ADVANCED", + [2] = "MAV_MODE_PROPERTY_NOT_USER_SELECTABLE", }, - ["UAVIONIX_ADSB_OUT_CONTROL_STATE"] = { - [1] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED", - [4] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND", - [8] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE", - [16] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED", - [32] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED", - [64] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED", - [128] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED", + ["GPS_SYSTEM_ERROR_FLAGS"] = { + [1] = "GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS", + [2] = "GPS_SYSTEM_ERROR_CONFIGURATION", + [4] = "GPS_SYSTEM_ERROR_SOFTWARE", + [8] = "GPS_SYSTEM_ERROR_ANTENNA", + [16] = "GPS_SYSTEM_ERROR_EVENT_CONGESTION", + [32] = "GPS_SYSTEM_ERROR_CPU_OVERLOAD", + [64] = "GPS_SYSTEM_ERROR_OUTPUT_CONGESTION", }, - ["UAVIONIX_ADSB_XBIT"] = { - [128] = "UAVIONIX_ADSB_XBIT_ENABLED", + ["GPS_AUTHENTICATION_STATE"] = { + [0] = "GPS_AUTHENTICATION_STATE_UNKNOWN", + [1] = "GPS_AUTHENTICATION_STATE_INITIALIZING", + [2] = "GPS_AUTHENTICATION_STATE_ERROR", + [3] = "GPS_AUTHENTICATION_STATE_OK", + [4] = "GPS_AUTHENTICATION_STATE_DISABLED", }, - ["UAVIONIX_ADSB_OUT_STATUS_STATE"] = { - [1] = "UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND", - [2] = "UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST", - [4] = "UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED", - [8] = "UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE", - [16] = "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED", - [32] = "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED", - [64] = "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED", - [128] = "UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED", + ["GPS_JAMMING_STATE"] = { + [0] = "GPS_JAMMING_STATE_UNKNOWN", + [1] = "GPS_JAMMING_STATE_OK", + [2] = "GPS_JAMMING_STATE_MITIGATED", + [3] = "GPS_JAMMING_STATE_DETECTED", }, - ["UAVIONIX_ADSB_OUT_STATUS_NIC_NACP"] = { - [1] = "UAVIONIX_ADSB_NIC_CR_20_NM", - [2] = "UAVIONIX_ADSB_NIC_CR_8_NM", - [3] = "UAVIONIX_ADSB_NIC_CR_4_NM", - [4] = "UAVIONIX_ADSB_NIC_CR_2_NM", - [5] = "UAVIONIX_ADSB_NIC_CR_1_NM", - [6] = "UAVIONIX_ADSB_NIC_CR_0_3_NM", - [7] = "UAVIONIX_ADSB_NIC_CR_0_2_NM", - [8] = "UAVIONIX_ADSB_NIC_CR_0_1_NM", - [9] = "UAVIONIX_ADSB_NIC_CR_75_M", - [10] = "UAVIONIX_ADSB_NIC_CR_25_M", - [11] = "UAVIONIX_ADSB_NIC_CR_7_5_M", - [16] = "UAVIONIX_ADSB_NACP_EPU_10_NM", - [32] = "UAVIONIX_ADSB_NACP_EPU_4_NM", - [48] = "UAVIONIX_ADSB_NACP_EPU_2_NM", - [64] = "UAVIONIX_ADSB_NACP_EPU_1_NM", - [80] = "UAVIONIX_ADSB_NACP_EPU_0_5_NM", - [96] = "UAVIONIX_ADSB_NACP_EPU_0_3_NM", - [112] = "UAVIONIX_ADSB_NACP_EPU_0_1_NM", - [128] = "UAVIONIX_ADSB_NACP_EPU_0_05_NM", - [144] = "UAVIONIX_ADSB_NACP_EPU_30_M", - [160] = "UAVIONIX_ADSB_NACP_EPU_10_M", - [176] = "UAVIONIX_ADSB_NACP_EPU_3_M", + ["GPS_SPOOFING_STATE"] = { + [0] = "GPS_SPOOFING_STATE_UNKNOWN", + [1] = "GPS_SPOOFING_STATE_OK", + [2] = "GPS_SPOOFING_STATE_MITIGATED", + [3] = "GPS_SPOOFING_STATE_DETECTED", }, - ["UAVIONIX_ADSB_OUT_STATUS_FAULT"] = { - [8] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL", - [16] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS", - [32] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL", - [64] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL", - [128] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", + ["GPS_RAIM_STATE"] = { + [0] = "GPS_RAIM_STATE_UNKNOWN", + [1] = "GPS_RAIM_STATE_DISABLED", + [2] = "GPS_RAIM_STATE_OK", + [3] = "GPS_RAIM_STATE_FAILED", }, ["ICAROUS_TRACK_BAND_TYPES"] = { [0] = "ICAROUS_TRACK_BAND_TYPE_NONE", @@ -2176,10 +2193,6 @@ 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", @@ -2415,6 +2428,305 @@ local enumEntryName = { [242] = "MAV_COMP_ID_TUNNEL_NODE", [250] = "MAV_COMP_ID_SYSTEM_CONTROL", }, + ["UALBERTA_AUTOPILOT_MODE"] = { + [1] = "MODE_MANUAL_DIRECT", + [2] = "MODE_MANUAL_SCALED", + [3] = "MODE_AUTO_PID_ATT", + [4] = "MODE_AUTO_PID_VEL", + [5] = "MODE_AUTO_PID_POS", + }, + ["UALBERTA_NAV_MODE"] = { + [1] = "NAV_AHRS_INIT", + [2] = "NAV_AHRS", + [3] = "NAV_INS_GPS_INIT", + [4] = "NAV_INS_GPS", + }, + ["UALBERTA_PILOT_MODE"] = { + [1] = "PILOT_MANUAL", + [2] = "PILOT_AUTO", + [3] = "PILOT_ROTO", + }, + ["UAVIONIX_ADSB_OUT_DYNAMIC_STATE"] = { + [1] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", + [2] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", + [4] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED", + [8] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND", + [16] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT", + }, + ["UAVIONIX_ADSB_OUT_RF_SELECT"] = { + [0] = "UAVIONIX_ADSB_OUT_RF_SELECT_STANDBY", + [1] = "UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED", + [2] = "UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED", + }, + ["UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX"] = { + [0] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0", + [1] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1", + [2] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D", + [3] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D", + [4] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS", + [5] = "UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK", + }, + ["UAVIONIX_ADSB_RF_HEALTH"] = { + [0] = "UAVIONIX_ADSB_RF_HEALTH_INITIALIZING", + [1] = "UAVIONIX_ADSB_RF_HEALTH_OK", + [2] = "UAVIONIX_ADSB_RF_HEALTH_FAIL_TX", + [16] = "UAVIONIX_ADSB_RF_HEALTH_FAIL_RX", + }, + ["UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE"] = { + [0] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA", + [1] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M", + [2] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M", + [3] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M", + [4] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M", + [5] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M", + [6] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M", + [7] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M", + [8] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M", + [9] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M", + [10] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M", + [11] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M", + [12] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M", + [13] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M", + [14] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M", + [15] = "UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M", + }, + ["UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT"] = { + [0] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA", + [1] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M", + [2] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M", + [3] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M", + [4] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M", + [5] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M", + [6] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M", + [7] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M", + }, + ["UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON"] = { + [0] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA", + [1] = "UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR", + }, + ["UAVIONIX_ADSB_EMERGENCY_STATUS"] = { + [0] = "UAVIONIX_ADSB_OUT_NO_EMERGENCY", + [1] = "UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY", + [2] = "UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY", + [3] = "UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY", + [4] = "UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY", + [5] = "UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY", + [6] = "UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY", + [7] = "UAVIONIX_ADSB_OUT_RESERVED", + }, + ["UAVIONIX_ADSB_OUT_CONTROL_STATE"] = { + [1] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED", + [4] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND", + [8] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE", + [16] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED", + [32] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED", + [64] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED", + [128] = "UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED", + }, + ["UAVIONIX_ADSB_XBIT"] = { + [128] = "UAVIONIX_ADSB_XBIT_ENABLED", + }, + ["UAVIONIX_ADSB_OUT_STATUS_STATE"] = { + [1] = "UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND", + [2] = "UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST", + [4] = "UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED", + [8] = "UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE", + [16] = "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED", + [32] = "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED", + [64] = "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED", + [128] = "UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED", + }, + ["UAVIONIX_ADSB_OUT_STATUS_NIC_NACP"] = { + [1] = "UAVIONIX_ADSB_NIC_CR_20_NM", + [2] = "UAVIONIX_ADSB_NIC_CR_8_NM", + [3] = "UAVIONIX_ADSB_NIC_CR_4_NM", + [4] = "UAVIONIX_ADSB_NIC_CR_2_NM", + [5] = "UAVIONIX_ADSB_NIC_CR_1_NM", + [6] = "UAVIONIX_ADSB_NIC_CR_0_3_NM", + [7] = "UAVIONIX_ADSB_NIC_CR_0_2_NM", + [8] = "UAVIONIX_ADSB_NIC_CR_0_1_NM", + [9] = "UAVIONIX_ADSB_NIC_CR_75_M", + [10] = "UAVIONIX_ADSB_NIC_CR_25_M", + [11] = "UAVIONIX_ADSB_NIC_CR_7_5_M", + [16] = "UAVIONIX_ADSB_NACP_EPU_10_NM", + [32] = "UAVIONIX_ADSB_NACP_EPU_4_NM", + [48] = "UAVIONIX_ADSB_NACP_EPU_2_NM", + [64] = "UAVIONIX_ADSB_NACP_EPU_1_NM", + [80] = "UAVIONIX_ADSB_NACP_EPU_0_5_NM", + [96] = "UAVIONIX_ADSB_NACP_EPU_0_3_NM", + [112] = "UAVIONIX_ADSB_NACP_EPU_0_1_NM", + [128] = "UAVIONIX_ADSB_NACP_EPU_0_05_NM", + [144] = "UAVIONIX_ADSB_NACP_EPU_30_M", + [160] = "UAVIONIX_ADSB_NACP_EPU_10_M", + [176] = "UAVIONIX_ADSB_NACP_EPU_3_M", + }, + ["UAVIONIX_ADSB_OUT_STATUS_FAULT"] = { + [8] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL", + [16] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS", + [32] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL", + [64] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL", + [128] = "UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", + }, + ["MAV_STORM32_TUNNEL_PAYLOAD_TYPE"] = { + [200] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_IN", + [201] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_OUT", + [202] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_IN", + [203] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_OUT", + [204] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_IN", + [205] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_OUT", + [206] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6", + [207] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7", + [208] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8", + [209] = "MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9", + }, + ["MAV_STORM32_GIMBAL_PREARM_FLAGS"] = { + [1] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_IS_NORMAL", + [2] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_IMUS_WORKING", + [4] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_MOTORS_WORKING", + [8] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_ENCODERS_WORKING", + [16] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_VOLTAGE_OK", + [32] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_VIRTUALCHANNELS_RECEIVING", + [64] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_MAVLINK_RECEIVING", + [128] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_STORM32LINK_QFIX", + [256] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_STORM32LINK_WORKING", + [512] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_CAMERA_CONNECTED", + [1024] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_AUX0_LOW", + [2048] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_AUX1_LOW", + [4096] = "MAV_STORM32_GIMBAL_PREARM_FLAGS_NTLOGGER_WORKING", + }, + ["MAV_STORM32_CAMERA_PREARM_FLAGS"] = { + [1] = "MAV_STORM32_CAMERA_PREARM_FLAGS_CONNECTED", + }, + ["MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS"] = { + [1] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", + [2] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", + [4] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", + [8] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", + [16] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", + [32] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", + [64] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", + [128] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", + [256] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", + [512] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", + [1024] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", + [2048] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW", + [65536] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW", + [131072] = "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC", + }, + ["MAV_STORM32_GIMBAL_DEVICE_FLAGS"] = { + [1] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", + [2] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", + [4] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", + [8] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", + [16] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", + [256] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", + [512] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", + [1024] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", + [2048] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", + [65535] = "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NONE", + }, + ["MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS"] = { + [1] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", + [2] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", + [4] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", + [8] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", + [16] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", + [32] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", + [64] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", + [128] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", + [256] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", + [32768] = "MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", + }, + ["MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS"] = { + [1] = "MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES", + [2] = "MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE", + }, + ["MAV_STORM32_GIMBAL_MANAGER_FLAGS"] = { + [0] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_NONE", + [1] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", + [2] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", + [4] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", + [8] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", + [16] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", + [32] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", + [64] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", + [128] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", + [256] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", + [512] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", + [1024] = "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", + }, + ["MAV_STORM32_GIMBAL_MANAGER_CLIENT"] = { + [0] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_NONE", + [1] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_ONBOARD", + [2] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_AUTOPILOT", + [3] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS", + [4] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA", + [5] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS2", + [6] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA2", + [7] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM", + [8] = "MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM2", + }, + ["MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS"] = { + [16384] = "MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE", + [32768] = "MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE", + }, + ["MAV_STORM32_GIMBAL_MANAGER_PROFILE"] = { + [0] = "MAV_STORM32_GIMBAL_MANAGER_PROFILE_DEFAULT", + [1] = "MAV_STORM32_GIMBAL_MANAGER_PROFILE_CUSTOM", + [2] = "MAV_STORM32_GIMBAL_MANAGER_PROFILE_COOPERATIVE", + [3] = "MAV_STORM32_GIMBAL_MANAGER_PROFILE_EXCLUSIVE", + [4] = "MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_COOPERATIVE", + [5] = "MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_EXCLUSIVE", + }, + ["MAV_STORM32_GIMBAL_ACTION"] = { + [1] = "MAV_STORM32_GIMBAL_ACTION_RECENTER", + [2] = "MAV_STORM32_GIMBAL_ACTION_CALIBRATION", + [3] = "MAV_STORM32_GIMBAL_ACTION_DISCOVER_MANAGER", + }, + ["MAV_QSHOT_MODE"] = { + [0] = "MAV_QSHOT_MODE_UNDEFINED", + [1] = "MAV_QSHOT_MODE_DEFAULT", + [2] = "MAV_QSHOT_MODE_GIMBAL_RETRACT", + [3] = "MAV_QSHOT_MODE_GIMBAL_NEUTRAL", + [4] = "MAV_QSHOT_MODE_GIMBAL_MISSION", + [5] = "MAV_QSHOT_MODE_GIMBAL_RC_CONTROL", + [6] = "MAV_QSHOT_MODE_POI_TARGETING", + [7] = "MAV_QSHOT_MODE_SYSID_TARGETING", + [8] = "MAV_QSHOT_MODE_CABLECAM_2POINT", + [9] = "MAV_QSHOT_MODE_HOME_TARGETING", + }, + ["MAV_AVSS_COMMAND_FAILURE_REASON"] = { + [1] = "PRS_NOT_STEADY", + [2] = "PRS_DTM_NOT_ARMED", + [3] = "PRS_OTM_NOT_ARMED", + }, + ["AVSS_M300_OPERATION_MODE"] = { + [0] = "MODE_M300_MANUAL_CTRL", + [1] = "MODE_M300_ATTITUDE", + [6] = "MODE_M300_P_GPS", + [9] = "MODE_M300_HOTPOINT_MODE", + [10] = "MODE_M300_ASSISTED_TAKEOFF", + [11] = "MODE_M300_AUTO_TAKEOFF", + [12] = "MODE_M300_AUTO_LANDING", + [15] = "MODE_M300_NAVI_GO_HOME", + [17] = "MODE_M300_NAVI_SDK_CTRL", + [31] = "MODE_M300_S_SPORT", + [33] = "MODE_M300_FORCE_AUTO_LANDING", + [38] = "MODE_M300_T_TRIPOD", + [40] = "MODE_M300_SEARCH_MODE", + [41] = "MODE_M300_ENGINE_START", + }, + ["AVSS_HORSEFLY_OPERATION_MODE"] = { + [0] = "MODE_HORSEFLY_MANUAL_CTRL", + [1] = "MODE_HORSEFLY_AUTO_TAKEOFF", + [2] = "MODE_HORSEFLY_AUTO_LANDING", + [3] = "MODE_HORSEFLY_NAVI_GO_HOME", + [4] = "MODE_HORSEFLY_DROP", + }, + ["AIRLINK_AUTH_RESPONSE_TYPE"] = { + [0] = "AIRLINK_ERROR_LOGIN_OR_PASS", + [1] = "AIRLINK_AUTH_OK", + }, } f.magic = ProtoField.uint8("mavlink_proto.magic", "Magic value / version", base.HEX, protocolVersions) f.length = ProtoField.uint8("mavlink_proto.length", "Payload length") @@ -2799,6 +3111,8 @@ f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4 = ProtoField.new("param4: Positions (float)" f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5 = ProtoField.new("param5: Roll Angle (float)", "mavlink_proto.cmd_MAV_CMD_OBLIQUE_SURVEY_param5", ftypes.FLOAT, nil) f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6 = ProtoField.new("param6: Pitch Angle (float)", "mavlink_proto.cmd_MAV_CMD_OBLIQUE_SURVEY_param6", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_SET_STANDARD_MODE_param1 = ProtoField.new("param1: Standard Mode (MAV_STANDARD_MODE)", "mavlink_proto.cmd_MAV_CMD_DO_SET_STANDARD_MODE_param1", ftypes.UINT32, enumEntryName.MAV_STANDARD_MODE) + f.cmd_MAV_CMD_MISSION_START_param1 = ProtoField.new("param1: First Item (float)", "mavlink_proto.cmd_MAV_CMD_MISSION_START_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_MISSION_START_param2 = ProtoField.new("param2: Last Item (float)", "mavlink_proto.cmd_MAV_CMD_MISSION_START_param2", ftypes.FLOAT, nil) @@ -2864,6 +3178,10 @@ f.cmd_MAV_CMD_JUMP_TAG_param1 = ProtoField.new("param1: Tag (float)", "mavlink_p f.cmd_MAV_CMD_DO_JUMP_TAG_param1 = ProtoField.new("param1: Tag (float)", "mavlink_proto.cmd_MAV_CMD_DO_JUMP_TAG_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_JUMP_TAG_param2 = ProtoField.new("param2: Repeat (float)", "mavlink_proto.cmd_MAV_CMD_DO_JUMP_TAG_param2", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param1 = ProtoField.new("param1: System ID (float)", "mavlink_proto.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param1", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param2 = ProtoField.new("param2: Component ID (float)", "mavlink_proto.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param2", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param3 = ProtoField.new("param3: Reboot (float)", "mavlink_proto.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param3", ftypes.FLOAT, nil) + f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1 = ProtoField.new("param1: Pitch angle (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2 = ProtoField.new("param2: Yaw angle (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2", ftypes.FLOAT, nil) 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) @@ -3033,6 +3351,8 @@ f.cmd_MAV_CMD_CAN_FORWARD_param1 = ProtoField.new("param1: bus (float)", "mavlin + + f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1 = ProtoField.new("param1: Takeoff Altitude (float)", "mavlink_proto.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1 = ProtoField.new("param1: Shot Mode (float)", "mavlink_proto.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1", ftypes.FLOAT, nil) @@ -3118,10 +3438,74 @@ f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5 = ProtoField.new("param5: Latitu f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6 = ProtoField.new("param6: Longitude (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6", ftypes.FLOAT, nil) f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7 = ProtoField.new("param7: Altitude (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param1 = ProtoField.new("param1: Wind speed (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param1", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param2 = ProtoField.new("param2: Wind speed accuracy (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param2", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param3 = ProtoField.new("param3: Direction (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param4 = ProtoField.new("param4: Direction accuracy (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param4", ftypes.FLOAT, nil) + f.cmd_MAV_CMD_SET_HAGL_param1 = ProtoField.new("param1: hagl (float)", "mavlink_proto.cmd_MAV_CMD_SET_HAGL_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_SET_HAGL_param2 = ProtoField.new("param2: accuracy (float)", "mavlink_proto.cmd_MAV_CMD_SET_HAGL_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_SET_HAGL_param3 = ProtoField.new("param3: timeout (float)", "mavlink_proto.cmd_MAV_CMD_SET_HAGL_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param1 = ProtoField.new("param1: Pitch angle (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param1", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param2 = ProtoField.new("param2: Yaw angle (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param2", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param3 = ProtoField.new("param3: Pitch rate (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param4 = ProtoField.new("param4: Yaw rate (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param4", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5 = ProtoField.new("param5: Gimbal device flags (MAV_STORM32_GIMBAL_DEVICE_FLAGS)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5", ftypes.UINT32, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", 17, nil, 1) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", 17, nil, 2) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 17, nil, 4) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 17, nil, 8) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", 17, nil, 16) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", 17, nil, 256) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", 17, nil, 512) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 17, nil, 1024) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", 17, nil, 2048) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", 17, nil, 65536) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6 = ProtoField.new("param6: Gimbal manager flags (MAV_STORM32_GIMBAL_MANAGER_FLAGS)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6", ftypes.UINT32, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", 11, nil, 1) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", 11, nil, 2) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", 11, nil, 4) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", 11, nil, 8) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", 11, nil, 16) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", 11, nil, 32) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", 11, nil, 64) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", 11, nil, 128) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", 11, nil, 256) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", 11, nil, 512) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", 11, nil, 1024) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param7 = ProtoField.new("param7: Gimbal ID and client ID (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param7", ftypes.FLOAT, nil) + +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param1 = ProtoField.new("param1: Profile (MAV_STORM32_GIMBAL_MANAGER_PROFILE)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param1", ftypes.UINT32, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_PROFILE) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2 = ProtoField.new("param2: Setup flags (MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2", ftypes.UINT32, nil) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2_flagMAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2.MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE", "MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE", 16, nil, 16384) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2_flagMAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2.MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE", "MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE", 16, nil, 32768) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param7 = ProtoField.new("param7: Gimbal ID (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param7", ftypes.FLOAT, nil) + +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param1 = ProtoField.new("param1: Action (MAV_STORM32_GIMBAL_ACTION)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param1", ftypes.UINT32, enumEntryName.MAV_STORM32_GIMBAL_ACTION) +f.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param7 = ProtoField.new("param7: Gimbal ID (float)", "mavlink_proto.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param7", ftypes.FLOAT, nil) + +f.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param1 = ProtoField.new("param1: Mode (MAV_QSHOT_MODE)", "mavlink_proto.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param1", ftypes.UINT32, enumEntryName.MAV_QSHOT_MODE) +f.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param2 = ProtoField.new("param2: Shot state or command (float)", "mavlink_proto.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param2", ftypes.FLOAT, nil) + +f.cmd_MAV_CMD_PRS_SET_ARM_param1 = ProtoField.new("param1: ARM status (float)", "mavlink_proto.cmd_MAV_CMD_PRS_SET_ARM_param1", ftypes.FLOAT, nil) + + + + +f.cmd_MAV_CMD_PRS_SET_ARM_ALTI_param1 = ProtoField.new("param1: Altitude (float)", "mavlink_proto.cmd_MAV_CMD_PRS_SET_ARM_ALTI_param1", ftypes.FLOAT, nil) + + + + +f.zVIDEO_STREAM_INFORMATION_camera_id = ProtoField.new("camera_id (uint8_t)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_camera_id", ftypes.UINT8, nil) +f.zVIDEO_STREAM_INFORMATION_status = ProtoField.new("status (uint8_t)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_status", ftypes.UINT8, nil) +f.zVIDEO_STREAM_INFORMATION_framerate = ProtoField.new("framerate (float)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_framerate", ftypes.FLOAT, nil) +f.zVIDEO_STREAM_INFORMATION_resolution_h = ProtoField.new("resolution_h (uint16_t)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_resolution_h", ftypes.UINT16, nil) +f.zVIDEO_STREAM_INFORMATION_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_resolution_v", ftypes.UINT16, nil) +f.zVIDEO_STREAM_INFORMATION_bitrate = ProtoField.new("bitrate (uint32_t)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_bitrate", ftypes.UINT32, nil) +f.zVIDEO_STREAM_INFORMATION_rotation = ProtoField.new("rotation (uint16_t)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_rotation", ftypes.UINT16, nil) +f.zVIDEO_STREAM_INFORMATION_uri = ProtoField.new("uri (char)", "mavlink_proto.zVIDEO_STREAM_INFORMATION_uri", ftypes.STRING, nil) f.SENSOR_OFFSETS_mag_ofs_x = ProtoField.new("mag_ofs_x (int16_t)", "mavlink_proto.SENSOR_OFFSETS_mag_ofs_x", ftypes.INT16, nil) f.SENSOR_OFFSETS_mag_ofs_y = ProtoField.new("mag_ofs_y (int16_t)", "mavlink_proto.SENSOR_OFFSETS_mag_ofs_y", ftypes.INT16, nil) @@ -4950,14 +5334,212 @@ f.ESC_TELEMETRY_29_TO_32_count_1 = ProtoField.new("count[1] (uint16_t)", "mavlin f.ESC_TELEMETRY_29_TO_32_count_2 = ProtoField.new("count[2] (uint16_t)", "mavlink_proto.ESC_TELEMETRY_29_TO_32_count_2", ftypes.UINT16, nil) f.ESC_TELEMETRY_29_TO_32_count_3 = ProtoField.new("count[3] (uint16_t)", "mavlink_proto.ESC_TELEMETRY_29_TO_32_count_3", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_camera_id = ProtoField.new("camera_id (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_camera_id", ftypes.UINT8, nil) -f.VIDEO_STREAM_INFORMATION99_status = ProtoField.new("status (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_status", ftypes.UINT8, nil) -f.VIDEO_STREAM_INFORMATION99_framerate = ProtoField.new("framerate (float)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_framerate", ftypes.FLOAT, nil) -f.VIDEO_STREAM_INFORMATION99_resolution_h = ProtoField.new("resolution_h (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_resolution_h", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_resolution_v", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_bitrate = ProtoField.new("bitrate (uint32_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_bitrate", ftypes.UINT32, nil) -f.VIDEO_STREAM_INFORMATION99_rotation = ProtoField.new("rotation (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_rotation", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_uri = ProtoField.new("uri (char)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_uri", ftypes.STRING, nil) +f.COMMAND_INT_STAMPED_utc_time = ProtoField.new("utc_time (uint32_t)", "mavlink_proto.COMMAND_INT_STAMPED_utc_time", ftypes.UINT32, nil) +f.COMMAND_INT_STAMPED_vehicle_timestamp = ProtoField.new("vehicle_timestamp (uint64_t)", "mavlink_proto.COMMAND_INT_STAMPED_vehicle_timestamp", ftypes.UINT64, nil) +f.COMMAND_INT_STAMPED_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.COMMAND_INT_STAMPED_target_system", ftypes.UINT8, nil) +f.COMMAND_INT_STAMPED_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.COMMAND_INT_STAMPED_target_component", ftypes.UINT8, nil) +f.COMMAND_INT_STAMPED_frame = ProtoField.new("frame (MAV_FRAME)", "mavlink_proto.COMMAND_INT_STAMPED_frame", ftypes.UINT8, enumEntryName.MAV_FRAME) +f.COMMAND_INT_STAMPED_command = ProtoField.new("command (MAV_CMD)", "mavlink_proto.COMMAND_INT_STAMPED_command", ftypes.UINT16, enumEntryName.MAV_CMD) +f.COMMAND_INT_STAMPED_current = ProtoField.new("current (uint8_t)", "mavlink_proto.COMMAND_INT_STAMPED_current", ftypes.UINT8, nil) +f.COMMAND_INT_STAMPED_autocontinue = ProtoField.new("autocontinue (uint8_t)", "mavlink_proto.COMMAND_INT_STAMPED_autocontinue", ftypes.UINT8, nil) +f.COMMAND_INT_STAMPED_param1 = ProtoField.new("param1 (float)", "mavlink_proto.COMMAND_INT_STAMPED_param1", ftypes.FLOAT, nil) +f.COMMAND_INT_STAMPED_param2 = ProtoField.new("param2 (float)", "mavlink_proto.COMMAND_INT_STAMPED_param2", ftypes.FLOAT, nil) +f.COMMAND_INT_STAMPED_param3 = ProtoField.new("param3 (float)", "mavlink_proto.COMMAND_INT_STAMPED_param3", ftypes.FLOAT, nil) +f.COMMAND_INT_STAMPED_param4 = ProtoField.new("param4 (float)", "mavlink_proto.COMMAND_INT_STAMPED_param4", ftypes.FLOAT, nil) +f.COMMAND_INT_STAMPED_x = ProtoField.new("x (int32_t)", "mavlink_proto.COMMAND_INT_STAMPED_x", ftypes.INT32, nil) +f.COMMAND_INT_STAMPED_y = ProtoField.new("y (int32_t)", "mavlink_proto.COMMAND_INT_STAMPED_y", ftypes.INT32, nil) +f.COMMAND_INT_STAMPED_z = ProtoField.new("z (float)", "mavlink_proto.COMMAND_INT_STAMPED_z", ftypes.FLOAT, nil) + +f.COMMAND_LONG_STAMPED_utc_time = ProtoField.new("utc_time (uint32_t)", "mavlink_proto.COMMAND_LONG_STAMPED_utc_time", ftypes.UINT32, nil) +f.COMMAND_LONG_STAMPED_vehicle_timestamp = ProtoField.new("vehicle_timestamp (uint64_t)", "mavlink_proto.COMMAND_LONG_STAMPED_vehicle_timestamp", ftypes.UINT64, nil) +f.COMMAND_LONG_STAMPED_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.COMMAND_LONG_STAMPED_target_system", ftypes.UINT8, nil) +f.COMMAND_LONG_STAMPED_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.COMMAND_LONG_STAMPED_target_component", ftypes.UINT8, nil) +f.COMMAND_LONG_STAMPED_command = ProtoField.new("command (MAV_CMD)", "mavlink_proto.COMMAND_LONG_STAMPED_command", ftypes.UINT16, enumEntryName.MAV_CMD) +f.COMMAND_LONG_STAMPED_confirmation = ProtoField.new("confirmation (uint8_t)", "mavlink_proto.COMMAND_LONG_STAMPED_confirmation", ftypes.UINT8, nil) +f.COMMAND_LONG_STAMPED_param1 = ProtoField.new("param1 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param1", ftypes.FLOAT, nil) +f.COMMAND_LONG_STAMPED_param2 = ProtoField.new("param2 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param2", ftypes.FLOAT, nil) +f.COMMAND_LONG_STAMPED_param3 = ProtoField.new("param3 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param3", ftypes.FLOAT, nil) +f.COMMAND_LONG_STAMPED_param4 = ProtoField.new("param4 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param4", ftypes.FLOAT, nil) +f.COMMAND_LONG_STAMPED_param5 = ProtoField.new("param5 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param5", ftypes.FLOAT, nil) +f.COMMAND_LONG_STAMPED_param6 = ProtoField.new("param6 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param6", ftypes.FLOAT, nil) +f.COMMAND_LONG_STAMPED_param7 = ProtoField.new("param7 (float)", "mavlink_proto.COMMAND_LONG_STAMPED_param7", ftypes.FLOAT, nil) + +f.SENS_POWER_adc121_vspb_volt = ProtoField.new("adc121_vspb_volt (float)", "mavlink_proto.SENS_POWER_adc121_vspb_volt", ftypes.FLOAT, nil) +f.SENS_POWER_adc121_cspb_amp = ProtoField.new("adc121_cspb_amp (float)", "mavlink_proto.SENS_POWER_adc121_cspb_amp", ftypes.FLOAT, nil) +f.SENS_POWER_adc121_cs1_amp = ProtoField.new("adc121_cs1_amp (float)", "mavlink_proto.SENS_POWER_adc121_cs1_amp", ftypes.FLOAT, nil) +f.SENS_POWER_adc121_cs2_amp = ProtoField.new("adc121_cs2_amp (float)", "mavlink_proto.SENS_POWER_adc121_cs2_amp", ftypes.FLOAT, nil) + +f.SENS_MPPT_mppt_timestamp = ProtoField.new("mppt_timestamp (uint64_t)", "mavlink_proto.SENS_MPPT_mppt_timestamp", ftypes.UINT64, nil) +f.SENS_MPPT_mppt1_volt = ProtoField.new("mppt1_volt (float)", "mavlink_proto.SENS_MPPT_mppt1_volt", ftypes.FLOAT, nil) +f.SENS_MPPT_mppt1_amp = ProtoField.new("mppt1_amp (float)", "mavlink_proto.SENS_MPPT_mppt1_amp", ftypes.FLOAT, nil) +f.SENS_MPPT_mppt1_pwm = ProtoField.new("mppt1_pwm (uint16_t)", "mavlink_proto.SENS_MPPT_mppt1_pwm", ftypes.UINT16, nil) +f.SENS_MPPT_mppt1_status = ProtoField.new("mppt1_status (uint8_t)", "mavlink_proto.SENS_MPPT_mppt1_status", ftypes.UINT8, nil) +f.SENS_MPPT_mppt2_volt = ProtoField.new("mppt2_volt (float)", "mavlink_proto.SENS_MPPT_mppt2_volt", ftypes.FLOAT, nil) +f.SENS_MPPT_mppt2_amp = ProtoField.new("mppt2_amp (float)", "mavlink_proto.SENS_MPPT_mppt2_amp", ftypes.FLOAT, nil) +f.SENS_MPPT_mppt2_pwm = ProtoField.new("mppt2_pwm (uint16_t)", "mavlink_proto.SENS_MPPT_mppt2_pwm", ftypes.UINT16, nil) +f.SENS_MPPT_mppt2_status = ProtoField.new("mppt2_status (uint8_t)", "mavlink_proto.SENS_MPPT_mppt2_status", ftypes.UINT8, nil) +f.SENS_MPPT_mppt3_volt = ProtoField.new("mppt3_volt (float)", "mavlink_proto.SENS_MPPT_mppt3_volt", ftypes.FLOAT, nil) +f.SENS_MPPT_mppt3_amp = ProtoField.new("mppt3_amp (float)", "mavlink_proto.SENS_MPPT_mppt3_amp", ftypes.FLOAT, nil) +f.SENS_MPPT_mppt3_pwm = ProtoField.new("mppt3_pwm (uint16_t)", "mavlink_proto.SENS_MPPT_mppt3_pwm", ftypes.UINT16, nil) +f.SENS_MPPT_mppt3_status = ProtoField.new("mppt3_status (uint8_t)", "mavlink_proto.SENS_MPPT_mppt3_status", ftypes.UINT8, nil) + +f.ASLCTRL_DATA_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.ASLCTRL_DATA_timestamp", ftypes.UINT64, nil) +f.ASLCTRL_DATA_aslctrl_mode = ProtoField.new("aslctrl_mode (uint8_t)", "mavlink_proto.ASLCTRL_DATA_aslctrl_mode", ftypes.UINT8, nil) +f.ASLCTRL_DATA_h = ProtoField.new("h (float)", "mavlink_proto.ASLCTRL_DATA_h", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_hRef = ProtoField.new("hRef (float)", "mavlink_proto.ASLCTRL_DATA_hRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_hRef_t = ProtoField.new("hRef_t (float)", "mavlink_proto.ASLCTRL_DATA_hRef_t", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_PitchAngle = ProtoField.new("PitchAngle (float)", "mavlink_proto.ASLCTRL_DATA_PitchAngle", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_PitchAngleRef = ProtoField.new("PitchAngleRef (float)", "mavlink_proto.ASLCTRL_DATA_PitchAngleRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_q = ProtoField.new("q (float)", "mavlink_proto.ASLCTRL_DATA_q", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_qRef = ProtoField.new("qRef (float)", "mavlink_proto.ASLCTRL_DATA_qRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_uElev = ProtoField.new("uElev (float)", "mavlink_proto.ASLCTRL_DATA_uElev", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_uThrot = ProtoField.new("uThrot (float)", "mavlink_proto.ASLCTRL_DATA_uThrot", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_uThrot2 = ProtoField.new("uThrot2 (float)", "mavlink_proto.ASLCTRL_DATA_uThrot2", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_nZ = ProtoField.new("nZ (float)", "mavlink_proto.ASLCTRL_DATA_nZ", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_AirspeedRef = ProtoField.new("AirspeedRef (float)", "mavlink_proto.ASLCTRL_DATA_AirspeedRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_SpoilersEngaged = ProtoField.new("SpoilersEngaged (uint8_t)", "mavlink_proto.ASLCTRL_DATA_SpoilersEngaged", ftypes.UINT8, nil) +f.ASLCTRL_DATA_YawAngle = ProtoField.new("YawAngle (float)", "mavlink_proto.ASLCTRL_DATA_YawAngle", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_YawAngleRef = ProtoField.new("YawAngleRef (float)", "mavlink_proto.ASLCTRL_DATA_YawAngleRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_RollAngle = ProtoField.new("RollAngle (float)", "mavlink_proto.ASLCTRL_DATA_RollAngle", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_RollAngleRef = ProtoField.new("RollAngleRef (float)", "mavlink_proto.ASLCTRL_DATA_RollAngleRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_p = ProtoField.new("p (float)", "mavlink_proto.ASLCTRL_DATA_p", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_pRef = ProtoField.new("pRef (float)", "mavlink_proto.ASLCTRL_DATA_pRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_r = ProtoField.new("r (float)", "mavlink_proto.ASLCTRL_DATA_r", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_rRef = ProtoField.new("rRef (float)", "mavlink_proto.ASLCTRL_DATA_rRef", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_uAil = ProtoField.new("uAil (float)", "mavlink_proto.ASLCTRL_DATA_uAil", ftypes.FLOAT, nil) +f.ASLCTRL_DATA_uRud = ProtoField.new("uRud (float)", "mavlink_proto.ASLCTRL_DATA_uRud", ftypes.FLOAT, nil) + +f.ASLCTRL_DEBUG_i32_1 = ProtoField.new("i32_1 (uint32_t)", "mavlink_proto.ASLCTRL_DEBUG_i32_1", ftypes.UINT32, nil) +f.ASLCTRL_DEBUG_i8_1 = ProtoField.new("i8_1 (uint8_t)", "mavlink_proto.ASLCTRL_DEBUG_i8_1", ftypes.UINT8, nil) +f.ASLCTRL_DEBUG_i8_2 = ProtoField.new("i8_2 (uint8_t)", "mavlink_proto.ASLCTRL_DEBUG_i8_2", ftypes.UINT8, nil) +f.ASLCTRL_DEBUG_f_1 = ProtoField.new("f_1 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_1", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_2 = ProtoField.new("f_2 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_2", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_3 = ProtoField.new("f_3 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_3", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_4 = ProtoField.new("f_4 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_4", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_5 = ProtoField.new("f_5 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_5", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_6 = ProtoField.new("f_6 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_6", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_7 = ProtoField.new("f_7 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_7", ftypes.FLOAT, nil) +f.ASLCTRL_DEBUG_f_8 = ProtoField.new("f_8 (float)", "mavlink_proto.ASLCTRL_DEBUG_f_8", ftypes.FLOAT, nil) + +f.ASLUAV_STATUS_LED_status = ProtoField.new("LED_status (uint8_t)", "mavlink_proto.ASLUAV_STATUS_LED_status", ftypes.UINT8, nil) +f.ASLUAV_STATUS_SATCOM_status = ProtoField.new("SATCOM_status (uint8_t)", "mavlink_proto.ASLUAV_STATUS_SATCOM_status", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_0 = ProtoField.new("Servo_status[0] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_0", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_1 = ProtoField.new("Servo_status[1] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_1", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_2 = ProtoField.new("Servo_status[2] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_2", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_3 = ProtoField.new("Servo_status[3] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_3", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_4 = ProtoField.new("Servo_status[4] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_4", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_5 = ProtoField.new("Servo_status[5] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_5", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_6 = ProtoField.new("Servo_status[6] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_6", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Servo_status_7 = ProtoField.new("Servo_status[7] (uint8_t)", "mavlink_proto.ASLUAV_STATUS_Servo_status_7", ftypes.UINT8, nil) +f.ASLUAV_STATUS_Motor_rpm = ProtoField.new("Motor_rpm (float)", "mavlink_proto.ASLUAV_STATUS_Motor_rpm", ftypes.FLOAT, nil) + +f.EKF_EXT_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.EKF_EXT_timestamp", ftypes.UINT64, nil) +f.EKF_EXT_Windspeed = ProtoField.new("Windspeed (float)", "mavlink_proto.EKF_EXT_Windspeed", ftypes.FLOAT, nil) +f.EKF_EXT_WindDir = ProtoField.new("WindDir (float)", "mavlink_proto.EKF_EXT_WindDir", ftypes.FLOAT, nil) +f.EKF_EXT_WindZ = ProtoField.new("WindZ (float)", "mavlink_proto.EKF_EXT_WindZ", ftypes.FLOAT, nil) +f.EKF_EXT_Airspeed = ProtoField.new("Airspeed (float)", "mavlink_proto.EKF_EXT_Airspeed", ftypes.FLOAT, nil) +f.EKF_EXT_beta = ProtoField.new("beta (float)", "mavlink_proto.EKF_EXT_beta", ftypes.FLOAT, nil) +f.EKF_EXT_alpha = ProtoField.new("alpha (float)", "mavlink_proto.EKF_EXT_alpha", ftypes.FLOAT, nil) + +f.ASL_OBCTRL_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.ASL_OBCTRL_timestamp", ftypes.UINT64, nil) +f.ASL_OBCTRL_uElev = ProtoField.new("uElev (float)", "mavlink_proto.ASL_OBCTRL_uElev", ftypes.FLOAT, nil) +f.ASL_OBCTRL_uThrot = ProtoField.new("uThrot (float)", "mavlink_proto.ASL_OBCTRL_uThrot", ftypes.FLOAT, nil) +f.ASL_OBCTRL_uThrot2 = ProtoField.new("uThrot2 (float)", "mavlink_proto.ASL_OBCTRL_uThrot2", ftypes.FLOAT, nil) +f.ASL_OBCTRL_uAilL = ProtoField.new("uAilL (float)", "mavlink_proto.ASL_OBCTRL_uAilL", ftypes.FLOAT, nil) +f.ASL_OBCTRL_uAilR = ProtoField.new("uAilR (float)", "mavlink_proto.ASL_OBCTRL_uAilR", ftypes.FLOAT, nil) +f.ASL_OBCTRL_uRud = ProtoField.new("uRud (float)", "mavlink_proto.ASL_OBCTRL_uRud", ftypes.FLOAT, nil) +f.ASL_OBCTRL_obctrl_status = ProtoField.new("obctrl_status (uint8_t)", "mavlink_proto.ASL_OBCTRL_obctrl_status", ftypes.UINT8, nil) + +f.SENS_ATMOS_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.SENS_ATMOS_timestamp", ftypes.UINT64, nil) +f.SENS_ATMOS_TempAmbient = ProtoField.new("TempAmbient (float)", "mavlink_proto.SENS_ATMOS_TempAmbient", ftypes.FLOAT, nil) +f.SENS_ATMOS_Humidity = ProtoField.new("Humidity (float)", "mavlink_proto.SENS_ATMOS_Humidity", ftypes.FLOAT, nil) + +f.SENS_BATMON_batmon_timestamp = ProtoField.new("batmon_timestamp (uint64_t)", "mavlink_proto.SENS_BATMON_batmon_timestamp", ftypes.UINT64, nil) +f.SENS_BATMON_temperature = ProtoField.new("temperature (float)", "mavlink_proto.SENS_BATMON_temperature", ftypes.FLOAT, nil) +f.SENS_BATMON_voltage = ProtoField.new("voltage (uint16_t)", "mavlink_proto.SENS_BATMON_voltage", ftypes.UINT16, nil) +f.SENS_BATMON_current = ProtoField.new("current (int16_t)", "mavlink_proto.SENS_BATMON_current", ftypes.INT16, nil) +f.SENS_BATMON_SoC = ProtoField.new("SoC (uint8_t)", "mavlink_proto.SENS_BATMON_SoC", ftypes.UINT8, nil) +f.SENS_BATMON_batterystatus = ProtoField.new("batterystatus (uint16_t)", "mavlink_proto.SENS_BATMON_batterystatus", ftypes.UINT16, nil) +f.SENS_BATMON_serialnumber = ProtoField.new("serialnumber (uint16_t)", "mavlink_proto.SENS_BATMON_serialnumber", ftypes.UINT16, nil) +f.SENS_BATMON_safetystatus = ProtoField.new("safetystatus (uint32_t)", "mavlink_proto.SENS_BATMON_safetystatus", ftypes.UINT32, nil) +f.SENS_BATMON_operationstatus = ProtoField.new("operationstatus (uint32_t)", "mavlink_proto.SENS_BATMON_operationstatus", ftypes.UINT32, nil) +f.SENS_BATMON_cellvoltage1 = ProtoField.new("cellvoltage1 (uint16_t)", "mavlink_proto.SENS_BATMON_cellvoltage1", ftypes.UINT16, nil) +f.SENS_BATMON_cellvoltage2 = ProtoField.new("cellvoltage2 (uint16_t)", "mavlink_proto.SENS_BATMON_cellvoltage2", ftypes.UINT16, nil) +f.SENS_BATMON_cellvoltage3 = ProtoField.new("cellvoltage3 (uint16_t)", "mavlink_proto.SENS_BATMON_cellvoltage3", ftypes.UINT16, nil) +f.SENS_BATMON_cellvoltage4 = ProtoField.new("cellvoltage4 (uint16_t)", "mavlink_proto.SENS_BATMON_cellvoltage4", ftypes.UINT16, nil) +f.SENS_BATMON_cellvoltage5 = ProtoField.new("cellvoltage5 (uint16_t)", "mavlink_proto.SENS_BATMON_cellvoltage5", ftypes.UINT16, nil) +f.SENS_BATMON_cellvoltage6 = ProtoField.new("cellvoltage6 (uint16_t)", "mavlink_proto.SENS_BATMON_cellvoltage6", ftypes.UINT16, nil) + +f.FW_SOARING_DATA_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.FW_SOARING_DATA_timestamp", ftypes.UINT64, nil) +f.FW_SOARING_DATA_timestampModeChanged = ProtoField.new("timestampModeChanged (uint64_t)", "mavlink_proto.FW_SOARING_DATA_timestampModeChanged", ftypes.UINT64, nil) +f.FW_SOARING_DATA_xW = ProtoField.new("xW (float)", "mavlink_proto.FW_SOARING_DATA_xW", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_xR = ProtoField.new("xR (float)", "mavlink_proto.FW_SOARING_DATA_xR", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_xLat = ProtoField.new("xLat (float)", "mavlink_proto.FW_SOARING_DATA_xLat", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_xLon = ProtoField.new("xLon (float)", "mavlink_proto.FW_SOARING_DATA_xLon", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_VarW = ProtoField.new("VarW (float)", "mavlink_proto.FW_SOARING_DATA_VarW", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_VarR = ProtoField.new("VarR (float)", "mavlink_proto.FW_SOARING_DATA_VarR", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_VarLat = ProtoField.new("VarLat (float)", "mavlink_proto.FW_SOARING_DATA_VarLat", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_VarLon = ProtoField.new("VarLon (float)", "mavlink_proto.FW_SOARING_DATA_VarLon", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_LoiterRadius = ProtoField.new("LoiterRadius (float)", "mavlink_proto.FW_SOARING_DATA_LoiterRadius", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_LoiterDirection = ProtoField.new("LoiterDirection (float)", "mavlink_proto.FW_SOARING_DATA_LoiterDirection", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_DistToSoarPoint = ProtoField.new("DistToSoarPoint (float)", "mavlink_proto.FW_SOARING_DATA_DistToSoarPoint", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_vSinkExp = ProtoField.new("vSinkExp (float)", "mavlink_proto.FW_SOARING_DATA_vSinkExp", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_z1_LocalUpdraftSpeed = ProtoField.new("z1_LocalUpdraftSpeed (float)", "mavlink_proto.FW_SOARING_DATA_z1_LocalUpdraftSpeed", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_z2_DeltaRoll = ProtoField.new("z2_DeltaRoll (float)", "mavlink_proto.FW_SOARING_DATA_z2_DeltaRoll", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_z1_exp = ProtoField.new("z1_exp (float)", "mavlink_proto.FW_SOARING_DATA_z1_exp", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_z2_exp = ProtoField.new("z2_exp (float)", "mavlink_proto.FW_SOARING_DATA_z2_exp", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_ThermalGSNorth = ProtoField.new("ThermalGSNorth (float)", "mavlink_proto.FW_SOARING_DATA_ThermalGSNorth", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_ThermalGSEast = ProtoField.new("ThermalGSEast (float)", "mavlink_proto.FW_SOARING_DATA_ThermalGSEast", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_TSE_dot = ProtoField.new("TSE_dot (float)", "mavlink_proto.FW_SOARING_DATA_TSE_dot", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_DebugVar1 = ProtoField.new("DebugVar1 (float)", "mavlink_proto.FW_SOARING_DATA_DebugVar1", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_DebugVar2 = ProtoField.new("DebugVar2 (float)", "mavlink_proto.FW_SOARING_DATA_DebugVar2", ftypes.FLOAT, nil) +f.FW_SOARING_DATA_ControlMode = ProtoField.new("ControlMode (uint8_t)", "mavlink_proto.FW_SOARING_DATA_ControlMode", ftypes.UINT8, nil) +f.FW_SOARING_DATA_valid = ProtoField.new("valid (uint8_t)", "mavlink_proto.FW_SOARING_DATA_valid", ftypes.UINT8, nil) + +f.SENSORPOD_STATUS_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.SENSORPOD_STATUS_timestamp", ftypes.UINT64, nil) +f.SENSORPOD_STATUS_visensor_rate_1 = ProtoField.new("visensor_rate_1 (uint8_t)", "mavlink_proto.SENSORPOD_STATUS_visensor_rate_1", ftypes.UINT8, nil) +f.SENSORPOD_STATUS_visensor_rate_2 = ProtoField.new("visensor_rate_2 (uint8_t)", "mavlink_proto.SENSORPOD_STATUS_visensor_rate_2", ftypes.UINT8, nil) +f.SENSORPOD_STATUS_visensor_rate_3 = ProtoField.new("visensor_rate_3 (uint8_t)", "mavlink_proto.SENSORPOD_STATUS_visensor_rate_3", ftypes.UINT8, nil) +f.SENSORPOD_STATUS_visensor_rate_4 = ProtoField.new("visensor_rate_4 (uint8_t)", "mavlink_proto.SENSORPOD_STATUS_visensor_rate_4", ftypes.UINT8, nil) +f.SENSORPOD_STATUS_recording_nodes_count = ProtoField.new("recording_nodes_count (uint8_t)", "mavlink_proto.SENSORPOD_STATUS_recording_nodes_count", ftypes.UINT8, nil) +f.SENSORPOD_STATUS_cpu_temp = ProtoField.new("cpu_temp (uint8_t)", "mavlink_proto.SENSORPOD_STATUS_cpu_temp", ftypes.UINT8, nil) +f.SENSORPOD_STATUS_free_space = ProtoField.new("free_space (uint16_t)", "mavlink_proto.SENSORPOD_STATUS_free_space", ftypes.UINT16, nil) + +f.SENS_POWER_BOARD_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.SENS_POWER_BOARD_timestamp", ftypes.UINT64, nil) +f.SENS_POWER_BOARD_pwr_brd_status = ProtoField.new("pwr_brd_status (uint8_t)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_status", ftypes.UINT8, nil) +f.SENS_POWER_BOARD_pwr_brd_led_status = ProtoField.new("pwr_brd_led_status (uint8_t)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_led_status", ftypes.UINT8, nil) +f.SENS_POWER_BOARD_pwr_brd_system_volt = ProtoField.new("pwr_brd_system_volt (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_system_volt", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_servo_volt = ProtoField.new("pwr_brd_servo_volt (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_servo_volt", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_digital_volt = ProtoField.new("pwr_brd_digital_volt (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_digital_volt", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_mot_l_amp = ProtoField.new("pwr_brd_mot_l_amp (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_mot_l_amp", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_mot_r_amp = ProtoField.new("pwr_brd_mot_r_amp (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_mot_r_amp", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_analog_amp = ProtoField.new("pwr_brd_analog_amp (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_analog_amp", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_digital_amp = ProtoField.new("pwr_brd_digital_amp (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_digital_amp", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_ext_amp = ProtoField.new("pwr_brd_ext_amp (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_ext_amp", ftypes.FLOAT, nil) +f.SENS_POWER_BOARD_pwr_brd_aux_amp = ProtoField.new("pwr_brd_aux_amp (float)", "mavlink_proto.SENS_POWER_BOARD_pwr_brd_aux_amp", ftypes.FLOAT, nil) + +f.GSM_LINK_STATUS_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.GSM_LINK_STATUS_timestamp", ftypes.UINT64, nil) +f.GSM_LINK_STATUS_gsm_modem_type = ProtoField.new("gsm_modem_type (GSM_MODEM_TYPE)", "mavlink_proto.GSM_LINK_STATUS_gsm_modem_type", ftypes.UINT8, enumEntryName.GSM_MODEM_TYPE) +f.GSM_LINK_STATUS_gsm_link_type = ProtoField.new("gsm_link_type (GSM_LINK_TYPE)", "mavlink_proto.GSM_LINK_STATUS_gsm_link_type", ftypes.UINT8, enumEntryName.GSM_LINK_TYPE) +f.GSM_LINK_STATUS_rssi = ProtoField.new("rssi (uint8_t)", "mavlink_proto.GSM_LINK_STATUS_rssi", ftypes.UINT8, nil) +f.GSM_LINK_STATUS_rsrp_rscp = ProtoField.new("rsrp_rscp (uint8_t)", "mavlink_proto.GSM_LINK_STATUS_rsrp_rscp", ftypes.UINT8, nil) +f.GSM_LINK_STATUS_sinr_ecio = ProtoField.new("sinr_ecio (uint8_t)", "mavlink_proto.GSM_LINK_STATUS_sinr_ecio", ftypes.UINT8, nil) +f.GSM_LINK_STATUS_rsrq = ProtoField.new("rsrq (uint8_t)", "mavlink_proto.GSM_LINK_STATUS_rsrq", ftypes.UINT8, nil) + +f.SATCOM_LINK_STATUS_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.SATCOM_LINK_STATUS_timestamp", ftypes.UINT64, nil) +f.SATCOM_LINK_STATUS_last_heartbeat = ProtoField.new("last_heartbeat (uint64_t)", "mavlink_proto.SATCOM_LINK_STATUS_last_heartbeat", ftypes.UINT64, nil) +f.SATCOM_LINK_STATUS_failed_sessions = ProtoField.new("failed_sessions (uint16_t)", "mavlink_proto.SATCOM_LINK_STATUS_failed_sessions", ftypes.UINT16, nil) +f.SATCOM_LINK_STATUS_successful_sessions = ProtoField.new("successful_sessions (uint16_t)", "mavlink_proto.SATCOM_LINK_STATUS_successful_sessions", ftypes.UINT16, nil) +f.SATCOM_LINK_STATUS_signal_quality = ProtoField.new("signal_quality (uint8_t)", "mavlink_proto.SATCOM_LINK_STATUS_signal_quality", ftypes.UINT8, nil) +f.SATCOM_LINK_STATUS_ring_pending = ProtoField.new("ring_pending (uint8_t)", "mavlink_proto.SATCOM_LINK_STATUS_ring_pending", ftypes.UINT8, nil) +f.SATCOM_LINK_STATUS_tx_session_pending = ProtoField.new("tx_session_pending (uint8_t)", "mavlink_proto.SATCOM_LINK_STATUS_tx_session_pending", ftypes.UINT8, nil) +f.SATCOM_LINK_STATUS_rx_session_pending = ProtoField.new("rx_session_pending (uint8_t)", "mavlink_proto.SATCOM_LINK_STATUS_rx_session_pending", ftypes.UINT8, nil) + +f.SENSOR_AIRFLOW_ANGLES_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.SENSOR_AIRFLOW_ANGLES_timestamp", ftypes.UINT64, nil) +f.SENSOR_AIRFLOW_ANGLES_angleofattack = ProtoField.new("angleofattack (float)", "mavlink_proto.SENSOR_AIRFLOW_ANGLES_angleofattack", ftypes.FLOAT, nil) +f.SENSOR_AIRFLOW_ANGLES_angleofattack_valid = ProtoField.new("angleofattack_valid (uint8_t)", "mavlink_proto.SENSOR_AIRFLOW_ANGLES_angleofattack_valid", ftypes.UINT8, nil) +f.SENSOR_AIRFLOW_ANGLES_sideslip = ProtoField.new("sideslip (float)", "mavlink_proto.SENSOR_AIRFLOW_ANGLES_sideslip", ftypes.FLOAT, nil) +f.SENSOR_AIRFLOW_ANGLES_sideslip_valid = ProtoField.new("sideslip_valid (uint8_t)", "mavlink_proto.SENSOR_AIRFLOW_ANGLES_sideslip_valid", ftypes.UINT8, nil) f.SYS_STATUS_onboard_control_sensors_present = ProtoField.new("onboard_control_sensors_present (MAV_SYS_STATUS_SENSOR)", "mavlink_proto.SYS_STATUS_onboard_control_sensors_present", ftypes.UINT32, nil) f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO", 31, nil, 1) @@ -9634,6 +10216,97 @@ f.ODOMETRY_reset_counter = ProtoField.new("reset_counter (uint8_t)", "mavlink_pr f.ODOMETRY_estimator_type = ProtoField.new("estimator_type (MAV_ESTIMATOR_TYPE)", "mavlink_proto.ODOMETRY_estimator_type", ftypes.UINT8, enumEntryName.MAV_ESTIMATOR_TYPE) f.ODOMETRY_quality = ProtoField.new("quality (int8_t)", "mavlink_proto.ODOMETRY_quality", ftypes.INT8, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_time_usec", ftypes.UINT64, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_valid_points = ProtoField.new("valid_points (uint8_t)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_valid_points", ftypes.UINT8, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_0 = ProtoField.new("pos_x[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_1 = ProtoField.new("pos_x[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_2 = ProtoField.new("pos_x[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_3 = ProtoField.new("pos_x[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_4 = ProtoField.new("pos_x[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_0 = ProtoField.new("pos_y[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_1 = ProtoField.new("pos_y[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_2 = ProtoField.new("pos_y[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_3 = ProtoField.new("pos_y[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_4 = ProtoField.new("pos_y[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_0 = ProtoField.new("pos_z[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_1 = ProtoField.new("pos_z[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_2 = ProtoField.new("pos_z[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_3 = ProtoField.new("pos_z[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_4 = ProtoField.new("pos_z[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_0 = ProtoField.new("vel_x[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_1 = ProtoField.new("vel_x[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_2 = ProtoField.new("vel_x[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_3 = ProtoField.new("vel_x[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_4 = ProtoField.new("vel_x[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_0 = ProtoField.new("vel_y[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_1 = ProtoField.new("vel_y[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_2 = ProtoField.new("vel_y[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_3 = ProtoField.new("vel_y[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_4 = ProtoField.new("vel_y[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_0 = ProtoField.new("vel_z[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_1 = ProtoField.new("vel_z[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_2 = ProtoField.new("vel_z[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_3 = ProtoField.new("vel_z[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_4 = ProtoField.new("vel_z[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_0 = ProtoField.new("acc_x[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_1 = ProtoField.new("acc_x[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_2 = ProtoField.new("acc_x[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_3 = ProtoField.new("acc_x[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_4 = ProtoField.new("acc_x[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_0 = ProtoField.new("acc_y[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_1 = ProtoField.new("acc_y[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_2 = ProtoField.new("acc_y[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_3 = ProtoField.new("acc_y[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_4 = ProtoField.new("acc_y[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_0 = ProtoField.new("acc_z[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_1 = ProtoField.new("acc_z[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_2 = ProtoField.new("acc_z[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_3 = ProtoField.new("acc_z[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_4 = ProtoField.new("acc_z[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_0 = ProtoField.new("pos_yaw[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_1 = ProtoField.new("pos_yaw[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_2 = ProtoField.new("pos_yaw[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_3 = ProtoField.new("pos_yaw[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_4 = ProtoField.new("pos_yaw[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_0 = ProtoField.new("vel_yaw[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_1 = ProtoField.new("vel_yaw[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_2 = ProtoField.new("vel_yaw[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_3 = ProtoField.new("vel_yaw[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_4 = ProtoField.new("vel_yaw[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_0 = ProtoField.new("command[0] (MAV_CMD)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_0", ftypes.UINT16, enumEntryName.MAV_CMD) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_1 = ProtoField.new("command[1] (MAV_CMD)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_1", ftypes.UINT16, enumEntryName.MAV_CMD) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_2 = ProtoField.new("command[2] (MAV_CMD)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_2", ftypes.UINT16, enumEntryName.MAV_CMD) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_3 = ProtoField.new("command[3] (MAV_CMD)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_3", ftypes.UINT16, enumEntryName.MAV_CMD) +f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_4 = ProtoField.new("command[4] (MAV_CMD)", "mavlink_proto.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_4", ftypes.UINT16, enumEntryName.MAV_CMD) + +f.TRAJECTORY_REPRESENTATION_BEZIER_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_time_usec", ftypes.UINT64, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_valid_points = ProtoField.new("valid_points (uint8_t)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_valid_points", ftypes.UINT8, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_0 = ProtoField.new("pos_x[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_1 = ProtoField.new("pos_x[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_2 = ProtoField.new("pos_x[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_3 = ProtoField.new("pos_x[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_4 = ProtoField.new("pos_x[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_0 = ProtoField.new("pos_y[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_1 = ProtoField.new("pos_y[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_2 = ProtoField.new("pos_y[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_3 = ProtoField.new("pos_y[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_4 = ProtoField.new("pos_y[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_0 = ProtoField.new("pos_z[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_1 = ProtoField.new("pos_z[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_2 = ProtoField.new("pos_z[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_3 = ProtoField.new("pos_z[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_4 = ProtoField.new("pos_z[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_delta_0 = ProtoField.new("delta[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_delta_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_delta_1 = ProtoField.new("delta[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_delta_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_delta_2 = ProtoField.new("delta[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_delta_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_delta_3 = ProtoField.new("delta[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_delta_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_delta_4 = ProtoField.new("delta[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_delta_4", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_0 = ProtoField.new("pos_yaw[0] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_0", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_1 = ProtoField.new("pos_yaw[1] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_1", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_2 = ProtoField.new("pos_yaw[2] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_2", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_3 = ProtoField.new("pos_yaw[3] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_3", ftypes.FLOAT, nil) +f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_4 = ProtoField.new("pos_yaw[4] (float)", "mavlink_proto.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_4", ftypes.FLOAT, nil) + f.ISBD_LINK_STATUS_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.ISBD_LINK_STATUS_timestamp", ftypes.UINT64, nil) f.ISBD_LINK_STATUS_last_heartbeat = ProtoField.new("last_heartbeat (uint64_t)", "mavlink_proto.ISBD_LINK_STATUS_last_heartbeat", ftypes.UINT64, nil) f.ISBD_LINK_STATUS_failed_sessions = ProtoField.new("failed_sessions (uint16_t)", "mavlink_proto.ISBD_LINK_STATUS_failed_sessions", ftypes.UINT16, nil) @@ -10599,6 +11272,286 @@ f.HYGROMETER_SENSOR_id = ProtoField.new("id (uint8_t)", "mavlink_proto.HYGROMETE f.HYGROMETER_SENSOR_temperature = ProtoField.new("temperature (int16_t)", "mavlink_proto.HYGROMETER_SENSOR_temperature", ftypes.INT16, nil) f.HYGROMETER_SENSOR_humidity = ProtoField.new("humidity (uint16_t)", "mavlink_proto.HYGROMETER_SENSOR_humidity", ftypes.UINT16, nil) +f.MISSION_CHECKSUM_mission_type = ProtoField.new("mission_type (MAV_MISSION_TYPE)", "mavlink_proto.MISSION_CHECKSUM_mission_type", ftypes.UINT8, enumEntryName.MAV_MISSION_TYPE) +f.MISSION_CHECKSUM_checksum = ProtoField.new("checksum (uint32_t)", "mavlink_proto.MISSION_CHECKSUM_checksum", ftypes.UINT32, nil) + +f.AIRSPEED_id = ProtoField.new("id (uint8_t)", "mavlink_proto.AIRSPEED_id", ftypes.UINT8, nil) +f.AIRSPEED_airspeed = ProtoField.new("airspeed (float)", "mavlink_proto.AIRSPEED_airspeed", ftypes.FLOAT, nil) +f.AIRSPEED_temperature = ProtoField.new("temperature (int16_t)", "mavlink_proto.AIRSPEED_temperature", ftypes.INT16, nil) +f.AIRSPEED_raw_press = ProtoField.new("raw_press (float)", "mavlink_proto.AIRSPEED_raw_press", ftypes.FLOAT, nil) +f.AIRSPEED_flags = ProtoField.new("flags (AIRSPEED_SENSOR_FLAGS)", "mavlink_proto.AIRSPEED_flags", ftypes.UINT8, nil) +f.AIRSPEED_flags_flagAIRSPEED_SENSOR_USING = ProtoField.bool("mavlink_proto.AIRSPEED_flags.AIRSPEED_SENSOR_USING", "AIRSPEED_SENSOR_USING", 2, nil, 1) +f.AIRSPEED_flags_flagAIRSPEED_SENSOR_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.AIRSPEED_flags.AIRSPEED_SENSOR_FLAGS_ENUM_END", "AIRSPEED_SENSOR_FLAGS_ENUM_END", 2, nil, 2) + +f.RADIO_RC_CHANNELS_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.RADIO_RC_CHANNELS_target_system", ftypes.UINT8, nil) +f.RADIO_RC_CHANNELS_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.RADIO_RC_CHANNELS_target_component", ftypes.UINT8, nil) +f.RADIO_RC_CHANNELS_time_last_update_ms = ProtoField.new("time_last_update_ms (uint32_t)", "mavlink_proto.RADIO_RC_CHANNELS_time_last_update_ms", ftypes.UINT32, nil) +f.RADIO_RC_CHANNELS_flags = ProtoField.new("flags (RADIO_RC_CHANNELS_FLAGS)", "mavlink_proto.RADIO_RC_CHANNELS_flags", ftypes.UINT16, nil) +f.RADIO_RC_CHANNELS_flags_flagRADIO_RC_CHANNELS_FLAGS_FAILSAFE = ProtoField.bool("mavlink_proto.RADIO_RC_CHANNELS_flags.RADIO_RC_CHANNELS_FLAGS_FAILSAFE", "RADIO_RC_CHANNELS_FLAGS_FAILSAFE", 2, nil, 1) +f.RADIO_RC_CHANNELS_flags_flagRADIO_RC_CHANNELS_FLAGS_OUTDATED = ProtoField.bool("mavlink_proto.RADIO_RC_CHANNELS_flags.RADIO_RC_CHANNELS_FLAGS_OUTDATED", "RADIO_RC_CHANNELS_FLAGS_OUTDATED", 2, nil, 2) +f.RADIO_RC_CHANNELS_count = ProtoField.new("count (uint8_t)", "mavlink_proto.RADIO_RC_CHANNELS_count", ftypes.UINT8, nil) +f.RADIO_RC_CHANNELS_channels_0 = ProtoField.new("channels[0] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_0", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_1 = ProtoField.new("channels[1] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_1", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_2 = ProtoField.new("channels[2] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_2", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_3 = ProtoField.new("channels[3] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_3", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_4 = ProtoField.new("channels[4] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_4", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_5 = ProtoField.new("channels[5] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_5", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_6 = ProtoField.new("channels[6] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_6", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_7 = ProtoField.new("channels[7] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_7", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_8 = ProtoField.new("channels[8] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_8", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_9 = ProtoField.new("channels[9] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_9", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_10 = ProtoField.new("channels[10] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_10", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_11 = ProtoField.new("channels[11] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_11", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_12 = ProtoField.new("channels[12] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_12", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_13 = ProtoField.new("channels[13] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_13", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_14 = ProtoField.new("channels[14] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_14", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_15 = ProtoField.new("channels[15] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_15", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_16 = ProtoField.new("channels[16] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_16", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_17 = ProtoField.new("channels[17] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_17", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_18 = ProtoField.new("channels[18] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_18", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_19 = ProtoField.new("channels[19] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_19", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_20 = ProtoField.new("channels[20] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_20", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_21 = ProtoField.new("channels[21] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_21", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_22 = ProtoField.new("channels[22] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_22", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_23 = ProtoField.new("channels[23] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_23", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_24 = ProtoField.new("channels[24] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_24", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_25 = ProtoField.new("channels[25] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_25", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_26 = ProtoField.new("channels[26] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_26", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_27 = ProtoField.new("channels[27] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_27", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_28 = ProtoField.new("channels[28] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_28", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_29 = ProtoField.new("channels[29] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_29", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_30 = ProtoField.new("channels[30] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_30", ftypes.INT16, nil) +f.RADIO_RC_CHANNELS_channels_31 = ProtoField.new("channels[31] (int16_t)", "mavlink_proto.RADIO_RC_CHANNELS_channels_31", ftypes.INT16, nil) + +f.AVAILABLE_MODES_number_modes = ProtoField.new("number_modes (uint8_t)", "mavlink_proto.AVAILABLE_MODES_number_modes", ftypes.UINT8, nil) +f.AVAILABLE_MODES_mode_index = ProtoField.new("mode_index (uint8_t)", "mavlink_proto.AVAILABLE_MODES_mode_index", ftypes.UINT8, nil) +f.AVAILABLE_MODES_standard_mode = ProtoField.new("standard_mode (MAV_STANDARD_MODE)", "mavlink_proto.AVAILABLE_MODES_standard_mode", ftypes.UINT8, enumEntryName.MAV_STANDARD_MODE) +f.AVAILABLE_MODES_custom_mode = ProtoField.new("custom_mode (uint32_t)", "mavlink_proto.AVAILABLE_MODES_custom_mode", ftypes.UINT32, nil) +f.AVAILABLE_MODES_properties = ProtoField.new("properties (MAV_MODE_PROPERTY)", "mavlink_proto.AVAILABLE_MODES_properties", ftypes.UINT32, nil) +f.AVAILABLE_MODES_properties_flagMAV_MODE_PROPERTY_ADVANCED = ProtoField.bool("mavlink_proto.AVAILABLE_MODES_properties.MAV_MODE_PROPERTY_ADVANCED", "MAV_MODE_PROPERTY_ADVANCED", 2, nil, 1) +f.AVAILABLE_MODES_properties_flagMAV_MODE_PROPERTY_NOT_USER_SELECTABLE = ProtoField.bool("mavlink_proto.AVAILABLE_MODES_properties.MAV_MODE_PROPERTY_NOT_USER_SELECTABLE", "MAV_MODE_PROPERTY_NOT_USER_SELECTABLE", 2, nil, 2) +f.AVAILABLE_MODES_mode_name = ProtoField.new("mode_name (char)", "mavlink_proto.AVAILABLE_MODES_mode_name", ftypes.STRING, nil) + +f.CURRENT_MODE_standard_mode = ProtoField.new("standard_mode (MAV_STANDARD_MODE)", "mavlink_proto.CURRENT_MODE_standard_mode", ftypes.UINT8, enumEntryName.MAV_STANDARD_MODE) +f.CURRENT_MODE_custom_mode = ProtoField.new("custom_mode (uint32_t)", "mavlink_proto.CURRENT_MODE_custom_mode", ftypes.UINT32, nil) +f.CURRENT_MODE_intended_custom_mode = ProtoField.new("intended_custom_mode (uint32_t)", "mavlink_proto.CURRENT_MODE_intended_custom_mode", ftypes.UINT32, nil) + +f.AVAILABLE_MODES_MONITOR_seq = ProtoField.new("seq (uint8_t)", "mavlink_proto.AVAILABLE_MODES_MONITOR_seq", ftypes.UINT8, nil) + +f.GNSS_INTEGRITY_id = ProtoField.new("id (uint8_t)", "mavlink_proto.GNSS_INTEGRITY_id", ftypes.UINT8, nil) +f.GNSS_INTEGRITY_system_errors = ProtoField.new("system_errors (GPS_SYSTEM_ERROR_FLAGS)", "mavlink_proto.GNSS_INTEGRITY_system_errors", ftypes.UINT32, nil) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_INCOMING_CORRECTIONS = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS", "GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS", 7, nil, 1) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_CONFIGURATION = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_CONFIGURATION", "GPS_SYSTEM_ERROR_CONFIGURATION", 7, nil, 2) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_SOFTWARE = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_SOFTWARE", "GPS_SYSTEM_ERROR_SOFTWARE", 7, nil, 4) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_ANTENNA = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_ANTENNA", "GPS_SYSTEM_ERROR_ANTENNA", 7, nil, 8) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_EVENT_CONGESTION = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_EVENT_CONGESTION", "GPS_SYSTEM_ERROR_EVENT_CONGESTION", 7, nil, 16) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_CPU_OVERLOAD = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_CPU_OVERLOAD", "GPS_SYSTEM_ERROR_CPU_OVERLOAD", 7, nil, 32) +f.GNSS_INTEGRITY_system_errors_flagGPS_SYSTEM_ERROR_OUTPUT_CONGESTION = ProtoField.bool("mavlink_proto.GNSS_INTEGRITY_system_errors.GPS_SYSTEM_ERROR_OUTPUT_CONGESTION", "GPS_SYSTEM_ERROR_OUTPUT_CONGESTION", 7, nil, 64) +f.GNSS_INTEGRITY_authentication_state = ProtoField.new("authentication_state (GPS_AUTHENTICATION_STATE)", "mavlink_proto.GNSS_INTEGRITY_authentication_state", ftypes.UINT8, enumEntryName.GPS_AUTHENTICATION_STATE) +f.GNSS_INTEGRITY_jamming_state = ProtoField.new("jamming_state (GPS_JAMMING_STATE)", "mavlink_proto.GNSS_INTEGRITY_jamming_state", ftypes.UINT8, enumEntryName.GPS_JAMMING_STATE) +f.GNSS_INTEGRITY_spoofing_state = ProtoField.new("spoofing_state (GPS_SPOOFING_STATE)", "mavlink_proto.GNSS_INTEGRITY_spoofing_state", ftypes.UINT8, enumEntryName.GPS_SPOOFING_STATE) +f.GNSS_INTEGRITY_raim_state = ProtoField.new("raim_state (GPS_RAIM_STATE)", "mavlink_proto.GNSS_INTEGRITY_raim_state", ftypes.UINT8, enumEntryName.GPS_RAIM_STATE) +f.GNSS_INTEGRITY_raim_hfom = ProtoField.new("raim_hfom (uint16_t)", "mavlink_proto.GNSS_INTEGRITY_raim_hfom", ftypes.UINT16, nil) +f.GNSS_INTEGRITY_raim_vfom = ProtoField.new("raim_vfom (uint16_t)", "mavlink_proto.GNSS_INTEGRITY_raim_vfom", ftypes.UINT16, nil) +f.GNSS_INTEGRITY_corrections_quality = ProtoField.new("corrections_quality (uint8_t)", "mavlink_proto.GNSS_INTEGRITY_corrections_quality", ftypes.UINT8, nil) +f.GNSS_INTEGRITY_system_status_summary = ProtoField.new("system_status_summary (uint8_t)", "mavlink_proto.GNSS_INTEGRITY_system_status_summary", ftypes.UINT8, nil) +f.GNSS_INTEGRITY_gnss_signal_quality = ProtoField.new("gnss_signal_quality (uint8_t)", "mavlink_proto.GNSS_INTEGRITY_gnss_signal_quality", ftypes.UINT8, nil) +f.GNSS_INTEGRITY_post_processing_quality = ProtoField.new("post_processing_quality (uint8_t)", "mavlink_proto.GNSS_INTEGRITY_post_processing_quality", ftypes.UINT8, nil) + +f.ICAROUS_HEARTBEAT_status = ProtoField.new("status (ICAROUS_FMS_STATE)", "mavlink_proto.ICAROUS_HEARTBEAT_status", ftypes.UINT8, enumEntryName.ICAROUS_FMS_STATE) + +f.ICAROUS_KINEMATIC_BANDS_numBands = ProtoField.new("numBands (int8_t)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_numBands", ftypes.INT8, nil) +f.ICAROUS_KINEMATIC_BANDS_type1 = ProtoField.new("type1 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type1", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) +f.ICAROUS_KINEMATIC_BANDS_min1 = ProtoField.new("min1 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min1", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_max1 = ProtoField.new("max1 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max1", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_type2 = ProtoField.new("type2 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type2", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) +f.ICAROUS_KINEMATIC_BANDS_min2 = ProtoField.new("min2 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min2", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_max2 = ProtoField.new("max2 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max2", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_type3 = ProtoField.new("type3 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type3", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) +f.ICAROUS_KINEMATIC_BANDS_min3 = ProtoField.new("min3 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min3", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_max3 = ProtoField.new("max3 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max3", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_type4 = ProtoField.new("type4 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type4", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) +f.ICAROUS_KINEMATIC_BANDS_min4 = ProtoField.new("min4 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min4", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_max4 = ProtoField.new("max4 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max4", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_type5 = ProtoField.new("type5 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type5", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) +f.ICAROUS_KINEMATIC_BANDS_min5 = ProtoField.new("min5 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min5", ftypes.FLOAT, nil) +f.ICAROUS_KINEMATIC_BANDS_max5 = ProtoField.new("max5 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max5", ftypes.FLOAT, nil) + +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) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", 8, nil, 1) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED", 8, nil, 2) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED", 8, nil, 4) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED", 8, nil, 8) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED", 8, nil, 16) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED", 8, nil, 32) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", 8, nil, 64) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED", 8, nil, 128) +f.HEARTBEAT_custom_mode = ProtoField.new("custom_mode (uint32_t)", "mavlink_proto.HEARTBEAT_custom_mode", ftypes.UINT32, nil) +f.HEARTBEAT_system_status = ProtoField.new("system_status (MAV_STATE)", "mavlink_proto.HEARTBEAT_system_status", ftypes.UINT8, enumEntryName.MAV_STATE) +f.HEARTBEAT_mavlink_version = ProtoField.new("mavlink_version (uint8_t)", "mavlink_proto.HEARTBEAT_mavlink_version", ftypes.UINT8, nil) + +f.ARRAY_TEST_0_v1 = ProtoField.new("v1 (uint8_t)", "mavlink_proto.ARRAY_TEST_0_v1", ftypes.UINT8, nil) +f.ARRAY_TEST_0_ar_i8_0 = ProtoField.new("ar_i8[0] (int8_t)", "mavlink_proto.ARRAY_TEST_0_ar_i8_0", ftypes.INT8, nil) +f.ARRAY_TEST_0_ar_i8_1 = ProtoField.new("ar_i8[1] (int8_t)", "mavlink_proto.ARRAY_TEST_0_ar_i8_1", ftypes.INT8, nil) +f.ARRAY_TEST_0_ar_i8_2 = ProtoField.new("ar_i8[2] (int8_t)", "mavlink_proto.ARRAY_TEST_0_ar_i8_2", ftypes.INT8, nil) +f.ARRAY_TEST_0_ar_i8_3 = ProtoField.new("ar_i8[3] (int8_t)", "mavlink_proto.ARRAY_TEST_0_ar_i8_3", ftypes.INT8, nil) +f.ARRAY_TEST_0_ar_u8_0 = ProtoField.new("ar_u8[0] (uint8_t)", "mavlink_proto.ARRAY_TEST_0_ar_u8_0", ftypes.UINT8, nil) +f.ARRAY_TEST_0_ar_u8_1 = ProtoField.new("ar_u8[1] (uint8_t)", "mavlink_proto.ARRAY_TEST_0_ar_u8_1", ftypes.UINT8, nil) +f.ARRAY_TEST_0_ar_u8_2 = ProtoField.new("ar_u8[2] (uint8_t)", "mavlink_proto.ARRAY_TEST_0_ar_u8_2", ftypes.UINT8, nil) +f.ARRAY_TEST_0_ar_u8_3 = ProtoField.new("ar_u8[3] (uint8_t)", "mavlink_proto.ARRAY_TEST_0_ar_u8_3", ftypes.UINT8, nil) +f.ARRAY_TEST_0_ar_u16_0 = ProtoField.new("ar_u16[0] (uint16_t)", "mavlink_proto.ARRAY_TEST_0_ar_u16_0", ftypes.UINT16, nil) +f.ARRAY_TEST_0_ar_u16_1 = ProtoField.new("ar_u16[1] (uint16_t)", "mavlink_proto.ARRAY_TEST_0_ar_u16_1", ftypes.UINT16, nil) +f.ARRAY_TEST_0_ar_u16_2 = ProtoField.new("ar_u16[2] (uint16_t)", "mavlink_proto.ARRAY_TEST_0_ar_u16_2", ftypes.UINT16, nil) +f.ARRAY_TEST_0_ar_u16_3 = ProtoField.new("ar_u16[3] (uint16_t)", "mavlink_proto.ARRAY_TEST_0_ar_u16_3", ftypes.UINT16, nil) +f.ARRAY_TEST_0_ar_u32_0 = ProtoField.new("ar_u32[0] (uint32_t)", "mavlink_proto.ARRAY_TEST_0_ar_u32_0", ftypes.UINT32, nil) +f.ARRAY_TEST_0_ar_u32_1 = ProtoField.new("ar_u32[1] (uint32_t)", "mavlink_proto.ARRAY_TEST_0_ar_u32_1", ftypes.UINT32, nil) +f.ARRAY_TEST_0_ar_u32_2 = ProtoField.new("ar_u32[2] (uint32_t)", "mavlink_proto.ARRAY_TEST_0_ar_u32_2", ftypes.UINT32, nil) +f.ARRAY_TEST_0_ar_u32_3 = ProtoField.new("ar_u32[3] (uint32_t)", "mavlink_proto.ARRAY_TEST_0_ar_u32_3", ftypes.UINT32, nil) + +f.ARRAY_TEST_1_ar_u32_0 = ProtoField.new("ar_u32[0] (uint32_t)", "mavlink_proto.ARRAY_TEST_1_ar_u32_0", ftypes.UINT32, nil) +f.ARRAY_TEST_1_ar_u32_1 = ProtoField.new("ar_u32[1] (uint32_t)", "mavlink_proto.ARRAY_TEST_1_ar_u32_1", ftypes.UINT32, nil) +f.ARRAY_TEST_1_ar_u32_2 = ProtoField.new("ar_u32[2] (uint32_t)", "mavlink_proto.ARRAY_TEST_1_ar_u32_2", ftypes.UINT32, nil) +f.ARRAY_TEST_1_ar_u32_3 = ProtoField.new("ar_u32[3] (uint32_t)", "mavlink_proto.ARRAY_TEST_1_ar_u32_3", ftypes.UINT32, nil) + +f.ARRAY_TEST_3_v = ProtoField.new("v (uint8_t)", "mavlink_proto.ARRAY_TEST_3_v", ftypes.UINT8, nil) +f.ARRAY_TEST_3_ar_u32_0 = ProtoField.new("ar_u32[0] (uint32_t)", "mavlink_proto.ARRAY_TEST_3_ar_u32_0", ftypes.UINT32, nil) +f.ARRAY_TEST_3_ar_u32_1 = ProtoField.new("ar_u32[1] (uint32_t)", "mavlink_proto.ARRAY_TEST_3_ar_u32_1", ftypes.UINT32, nil) +f.ARRAY_TEST_3_ar_u32_2 = ProtoField.new("ar_u32[2] (uint32_t)", "mavlink_proto.ARRAY_TEST_3_ar_u32_2", ftypes.UINT32, nil) +f.ARRAY_TEST_3_ar_u32_3 = ProtoField.new("ar_u32[3] (uint32_t)", "mavlink_proto.ARRAY_TEST_3_ar_u32_3", ftypes.UINT32, nil) + +f.ARRAY_TEST_4_ar_u32_0 = ProtoField.new("ar_u32[0] (uint32_t)", "mavlink_proto.ARRAY_TEST_4_ar_u32_0", ftypes.UINT32, nil) +f.ARRAY_TEST_4_ar_u32_1 = ProtoField.new("ar_u32[1] (uint32_t)", "mavlink_proto.ARRAY_TEST_4_ar_u32_1", ftypes.UINT32, nil) +f.ARRAY_TEST_4_ar_u32_2 = ProtoField.new("ar_u32[2] (uint32_t)", "mavlink_proto.ARRAY_TEST_4_ar_u32_2", ftypes.UINT32, nil) +f.ARRAY_TEST_4_ar_u32_3 = ProtoField.new("ar_u32[3] (uint32_t)", "mavlink_proto.ARRAY_TEST_4_ar_u32_3", ftypes.UINT32, nil) +f.ARRAY_TEST_4_v = ProtoField.new("v (uint8_t)", "mavlink_proto.ARRAY_TEST_4_v", ftypes.UINT8, nil) + +f.ARRAY_TEST_5_c1 = ProtoField.new("c1 (char)", "mavlink_proto.ARRAY_TEST_5_c1", ftypes.STRING, nil) +f.ARRAY_TEST_5_c2 = ProtoField.new("c2 (char)", "mavlink_proto.ARRAY_TEST_5_c2", ftypes.STRING, nil) + +f.ARRAY_TEST_6_v1 = ProtoField.new("v1 (uint8_t)", "mavlink_proto.ARRAY_TEST_6_v1", ftypes.UINT8, nil) +f.ARRAY_TEST_6_v2 = ProtoField.new("v2 (uint16_t)", "mavlink_proto.ARRAY_TEST_6_v2", ftypes.UINT16, nil) +f.ARRAY_TEST_6_v3 = ProtoField.new("v3 (uint32_t)", "mavlink_proto.ARRAY_TEST_6_v3", ftypes.UINT32, nil) +f.ARRAY_TEST_6_ar_u32_0 = ProtoField.new("ar_u32[0] (uint32_t)", "mavlink_proto.ARRAY_TEST_6_ar_u32_0", ftypes.UINT32, nil) +f.ARRAY_TEST_6_ar_u32_1 = ProtoField.new("ar_u32[1] (uint32_t)", "mavlink_proto.ARRAY_TEST_6_ar_u32_1", ftypes.UINT32, nil) +f.ARRAY_TEST_6_ar_i32_0 = ProtoField.new("ar_i32[0] (int32_t)", "mavlink_proto.ARRAY_TEST_6_ar_i32_0", ftypes.INT32, nil) +f.ARRAY_TEST_6_ar_i32_1 = ProtoField.new("ar_i32[1] (int32_t)", "mavlink_proto.ARRAY_TEST_6_ar_i32_1", ftypes.INT32, nil) +f.ARRAY_TEST_6_ar_u16_0 = ProtoField.new("ar_u16[0] (uint16_t)", "mavlink_proto.ARRAY_TEST_6_ar_u16_0", ftypes.UINT16, nil) +f.ARRAY_TEST_6_ar_u16_1 = ProtoField.new("ar_u16[1] (uint16_t)", "mavlink_proto.ARRAY_TEST_6_ar_u16_1", ftypes.UINT16, nil) +f.ARRAY_TEST_6_ar_i16_0 = ProtoField.new("ar_i16[0] (int16_t)", "mavlink_proto.ARRAY_TEST_6_ar_i16_0", ftypes.INT16, nil) +f.ARRAY_TEST_6_ar_i16_1 = ProtoField.new("ar_i16[1] (int16_t)", "mavlink_proto.ARRAY_TEST_6_ar_i16_1", ftypes.INT16, nil) +f.ARRAY_TEST_6_ar_u8_0 = ProtoField.new("ar_u8[0] (uint8_t)", "mavlink_proto.ARRAY_TEST_6_ar_u8_0", ftypes.UINT8, nil) +f.ARRAY_TEST_6_ar_u8_1 = ProtoField.new("ar_u8[1] (uint8_t)", "mavlink_proto.ARRAY_TEST_6_ar_u8_1", ftypes.UINT8, nil) +f.ARRAY_TEST_6_ar_i8_0 = ProtoField.new("ar_i8[0] (int8_t)", "mavlink_proto.ARRAY_TEST_6_ar_i8_0", ftypes.INT8, nil) +f.ARRAY_TEST_6_ar_i8_1 = ProtoField.new("ar_i8[1] (int8_t)", "mavlink_proto.ARRAY_TEST_6_ar_i8_1", ftypes.INT8, nil) +f.ARRAY_TEST_6_ar_c = ProtoField.new("ar_c (char)", "mavlink_proto.ARRAY_TEST_6_ar_c", ftypes.STRING, nil) +f.ARRAY_TEST_6_ar_d_0 = ProtoField.new("ar_d[0] (double)", "mavlink_proto.ARRAY_TEST_6_ar_d_0", ftypes.DOUBLE, nil) +f.ARRAY_TEST_6_ar_d_1 = ProtoField.new("ar_d[1] (double)", "mavlink_proto.ARRAY_TEST_6_ar_d_1", ftypes.DOUBLE, nil) +f.ARRAY_TEST_6_ar_f_0 = ProtoField.new("ar_f[0] (float)", "mavlink_proto.ARRAY_TEST_6_ar_f_0", ftypes.FLOAT, nil) +f.ARRAY_TEST_6_ar_f_1 = ProtoField.new("ar_f[1] (float)", "mavlink_proto.ARRAY_TEST_6_ar_f_1", ftypes.FLOAT, nil) + +f.ARRAY_TEST_7_ar_d_0 = ProtoField.new("ar_d[0] (double)", "mavlink_proto.ARRAY_TEST_7_ar_d_0", ftypes.DOUBLE, nil) +f.ARRAY_TEST_7_ar_d_1 = ProtoField.new("ar_d[1] (double)", "mavlink_proto.ARRAY_TEST_7_ar_d_1", ftypes.DOUBLE, nil) +f.ARRAY_TEST_7_ar_f_0 = ProtoField.new("ar_f[0] (float)", "mavlink_proto.ARRAY_TEST_7_ar_f_0", ftypes.FLOAT, nil) +f.ARRAY_TEST_7_ar_f_1 = ProtoField.new("ar_f[1] (float)", "mavlink_proto.ARRAY_TEST_7_ar_f_1", ftypes.FLOAT, nil) +f.ARRAY_TEST_7_ar_u32_0 = ProtoField.new("ar_u32[0] (uint32_t)", "mavlink_proto.ARRAY_TEST_7_ar_u32_0", ftypes.UINT32, nil) +f.ARRAY_TEST_7_ar_u32_1 = ProtoField.new("ar_u32[1] (uint32_t)", "mavlink_proto.ARRAY_TEST_7_ar_u32_1", ftypes.UINT32, nil) +f.ARRAY_TEST_7_ar_i32_0 = ProtoField.new("ar_i32[0] (int32_t)", "mavlink_proto.ARRAY_TEST_7_ar_i32_0", ftypes.INT32, nil) +f.ARRAY_TEST_7_ar_i32_1 = ProtoField.new("ar_i32[1] (int32_t)", "mavlink_proto.ARRAY_TEST_7_ar_i32_1", ftypes.INT32, nil) +f.ARRAY_TEST_7_ar_u16_0 = ProtoField.new("ar_u16[0] (uint16_t)", "mavlink_proto.ARRAY_TEST_7_ar_u16_0", ftypes.UINT16, nil) +f.ARRAY_TEST_7_ar_u16_1 = ProtoField.new("ar_u16[1] (uint16_t)", "mavlink_proto.ARRAY_TEST_7_ar_u16_1", ftypes.UINT16, nil) +f.ARRAY_TEST_7_ar_i16_0 = ProtoField.new("ar_i16[0] (int16_t)", "mavlink_proto.ARRAY_TEST_7_ar_i16_0", ftypes.INT16, nil) +f.ARRAY_TEST_7_ar_i16_1 = ProtoField.new("ar_i16[1] (int16_t)", "mavlink_proto.ARRAY_TEST_7_ar_i16_1", ftypes.INT16, nil) +f.ARRAY_TEST_7_ar_u8_0 = ProtoField.new("ar_u8[0] (uint8_t)", "mavlink_proto.ARRAY_TEST_7_ar_u8_0", ftypes.UINT8, nil) +f.ARRAY_TEST_7_ar_u8_1 = ProtoField.new("ar_u8[1] (uint8_t)", "mavlink_proto.ARRAY_TEST_7_ar_u8_1", ftypes.UINT8, nil) +f.ARRAY_TEST_7_ar_i8_0 = ProtoField.new("ar_i8[0] (int8_t)", "mavlink_proto.ARRAY_TEST_7_ar_i8_0", ftypes.INT8, nil) +f.ARRAY_TEST_7_ar_i8_1 = ProtoField.new("ar_i8[1] (int8_t)", "mavlink_proto.ARRAY_TEST_7_ar_i8_1", ftypes.INT8, nil) +f.ARRAY_TEST_7_ar_c = ProtoField.new("ar_c (char)", "mavlink_proto.ARRAY_TEST_7_ar_c", ftypes.STRING, nil) + +f.ARRAY_TEST_8_v3 = ProtoField.new("v3 (uint32_t)", "mavlink_proto.ARRAY_TEST_8_v3", ftypes.UINT32, nil) +f.ARRAY_TEST_8_ar_d_0 = ProtoField.new("ar_d[0] (double)", "mavlink_proto.ARRAY_TEST_8_ar_d_0", ftypes.DOUBLE, nil) +f.ARRAY_TEST_8_ar_d_1 = ProtoField.new("ar_d[1] (double)", "mavlink_proto.ARRAY_TEST_8_ar_d_1", ftypes.DOUBLE, nil) +f.ARRAY_TEST_8_ar_u16_0 = ProtoField.new("ar_u16[0] (uint16_t)", "mavlink_proto.ARRAY_TEST_8_ar_u16_0", ftypes.UINT16, nil) +f.ARRAY_TEST_8_ar_u16_1 = ProtoField.new("ar_u16[1] (uint16_t)", "mavlink_proto.ARRAY_TEST_8_ar_u16_1", ftypes.UINT16, nil) + +f.TEST_TYPES_c = ProtoField.new("c (char)", "mavlink_proto.TEST_TYPES_c", ftypes.STRING, nil) +f.TEST_TYPES_s = ProtoField.new("s (char)", "mavlink_proto.TEST_TYPES_s", ftypes.STRING, nil) +f.TEST_TYPES_u8 = ProtoField.new("u8 (uint8_t)", "mavlink_proto.TEST_TYPES_u8", ftypes.UINT8, nil) +f.TEST_TYPES_u16 = ProtoField.new("u16 (uint16_t)", "mavlink_proto.TEST_TYPES_u16", ftypes.UINT16, nil) +f.TEST_TYPES_u32 = ProtoField.new("u32 (uint32_t)", "mavlink_proto.TEST_TYPES_u32", ftypes.UINT32, nil) +f.TEST_TYPES_u64 = ProtoField.new("u64 (uint64_t)", "mavlink_proto.TEST_TYPES_u64", ftypes.UINT64, nil) +f.TEST_TYPES_s8 = ProtoField.new("s8 (int8_t)", "mavlink_proto.TEST_TYPES_s8", ftypes.INT8, nil) +f.TEST_TYPES_s16 = ProtoField.new("s16 (int16_t)", "mavlink_proto.TEST_TYPES_s16", ftypes.INT16, nil) +f.TEST_TYPES_s32 = ProtoField.new("s32 (int32_t)", "mavlink_proto.TEST_TYPES_s32", ftypes.INT32, nil) +f.TEST_TYPES_s64 = ProtoField.new("s64 (int64_t)", "mavlink_proto.TEST_TYPES_s64", ftypes.INT64, nil) +f.TEST_TYPES_f = ProtoField.new("f (float)", "mavlink_proto.TEST_TYPES_f", ftypes.FLOAT, nil) +f.TEST_TYPES_d = ProtoField.new("d (double)", "mavlink_proto.TEST_TYPES_d", ftypes.DOUBLE, nil) +f.TEST_TYPES_u8_array_0 = ProtoField.new("u8_array[0] (uint8_t)", "mavlink_proto.TEST_TYPES_u8_array_0", ftypes.UINT8, nil) +f.TEST_TYPES_u8_array_1 = ProtoField.new("u8_array[1] (uint8_t)", "mavlink_proto.TEST_TYPES_u8_array_1", ftypes.UINT8, nil) +f.TEST_TYPES_u8_array_2 = ProtoField.new("u8_array[2] (uint8_t)", "mavlink_proto.TEST_TYPES_u8_array_2", ftypes.UINT8, nil) +f.TEST_TYPES_u16_array_0 = ProtoField.new("u16_array[0] (uint16_t)", "mavlink_proto.TEST_TYPES_u16_array_0", ftypes.UINT16, nil) +f.TEST_TYPES_u16_array_1 = ProtoField.new("u16_array[1] (uint16_t)", "mavlink_proto.TEST_TYPES_u16_array_1", ftypes.UINT16, nil) +f.TEST_TYPES_u16_array_2 = ProtoField.new("u16_array[2] (uint16_t)", "mavlink_proto.TEST_TYPES_u16_array_2", ftypes.UINT16, nil) +f.TEST_TYPES_u32_array_0 = ProtoField.new("u32_array[0] (uint32_t)", "mavlink_proto.TEST_TYPES_u32_array_0", ftypes.UINT32, nil) +f.TEST_TYPES_u32_array_1 = ProtoField.new("u32_array[1] (uint32_t)", "mavlink_proto.TEST_TYPES_u32_array_1", ftypes.UINT32, nil) +f.TEST_TYPES_u32_array_2 = ProtoField.new("u32_array[2] (uint32_t)", "mavlink_proto.TEST_TYPES_u32_array_2", ftypes.UINT32, nil) +f.TEST_TYPES_u64_array_0 = ProtoField.new("u64_array[0] (uint64_t)", "mavlink_proto.TEST_TYPES_u64_array_0", ftypes.UINT64, nil) +f.TEST_TYPES_u64_array_1 = ProtoField.new("u64_array[1] (uint64_t)", "mavlink_proto.TEST_TYPES_u64_array_1", ftypes.UINT64, nil) +f.TEST_TYPES_u64_array_2 = ProtoField.new("u64_array[2] (uint64_t)", "mavlink_proto.TEST_TYPES_u64_array_2", ftypes.UINT64, nil) +f.TEST_TYPES_s8_array_0 = ProtoField.new("s8_array[0] (int8_t)", "mavlink_proto.TEST_TYPES_s8_array_0", ftypes.INT8, nil) +f.TEST_TYPES_s8_array_1 = ProtoField.new("s8_array[1] (int8_t)", "mavlink_proto.TEST_TYPES_s8_array_1", ftypes.INT8, nil) +f.TEST_TYPES_s8_array_2 = ProtoField.new("s8_array[2] (int8_t)", "mavlink_proto.TEST_TYPES_s8_array_2", ftypes.INT8, nil) +f.TEST_TYPES_s16_array_0 = ProtoField.new("s16_array[0] (int16_t)", "mavlink_proto.TEST_TYPES_s16_array_0", ftypes.INT16, nil) +f.TEST_TYPES_s16_array_1 = ProtoField.new("s16_array[1] (int16_t)", "mavlink_proto.TEST_TYPES_s16_array_1", ftypes.INT16, nil) +f.TEST_TYPES_s16_array_2 = ProtoField.new("s16_array[2] (int16_t)", "mavlink_proto.TEST_TYPES_s16_array_2", ftypes.INT16, nil) +f.TEST_TYPES_s32_array_0 = ProtoField.new("s32_array[0] (int32_t)", "mavlink_proto.TEST_TYPES_s32_array_0", ftypes.INT32, nil) +f.TEST_TYPES_s32_array_1 = ProtoField.new("s32_array[1] (int32_t)", "mavlink_proto.TEST_TYPES_s32_array_1", ftypes.INT32, nil) +f.TEST_TYPES_s32_array_2 = ProtoField.new("s32_array[2] (int32_t)", "mavlink_proto.TEST_TYPES_s32_array_2", ftypes.INT32, nil) +f.TEST_TYPES_s64_array_0 = ProtoField.new("s64_array[0] (int64_t)", "mavlink_proto.TEST_TYPES_s64_array_0", ftypes.INT64, nil) +f.TEST_TYPES_s64_array_1 = ProtoField.new("s64_array[1] (int64_t)", "mavlink_proto.TEST_TYPES_s64_array_1", ftypes.INT64, nil) +f.TEST_TYPES_s64_array_2 = ProtoField.new("s64_array[2] (int64_t)", "mavlink_proto.TEST_TYPES_s64_array_2", ftypes.INT64, nil) +f.TEST_TYPES_f_array_0 = ProtoField.new("f_array[0] (float)", "mavlink_proto.TEST_TYPES_f_array_0", ftypes.FLOAT, nil) +f.TEST_TYPES_f_array_1 = ProtoField.new("f_array[1] (float)", "mavlink_proto.TEST_TYPES_f_array_1", ftypes.FLOAT, nil) +f.TEST_TYPES_f_array_2 = ProtoField.new("f_array[2] (float)", "mavlink_proto.TEST_TYPES_f_array_2", ftypes.FLOAT, nil) +f.TEST_TYPES_d_array_0 = ProtoField.new("d_array[0] (double)", "mavlink_proto.TEST_TYPES_d_array_0", ftypes.DOUBLE, nil) +f.TEST_TYPES_d_array_1 = ProtoField.new("d_array[1] (double)", "mavlink_proto.TEST_TYPES_d_array_1", ftypes.DOUBLE, nil) +f.TEST_TYPES_d_array_2 = ProtoField.new("d_array[2] (double)", "mavlink_proto.TEST_TYPES_d_array_2", ftypes.DOUBLE, nil) + +f.NAV_FILTER_BIAS_usec = ProtoField.new("usec (uint64_t)", "mavlink_proto.NAV_FILTER_BIAS_usec", ftypes.UINT64, nil) +f.NAV_FILTER_BIAS_accel_0 = ProtoField.new("accel_0 (float)", "mavlink_proto.NAV_FILTER_BIAS_accel_0", ftypes.FLOAT, nil) +f.NAV_FILTER_BIAS_accel_1 = ProtoField.new("accel_1 (float)", "mavlink_proto.NAV_FILTER_BIAS_accel_1", ftypes.FLOAT, nil) +f.NAV_FILTER_BIAS_accel_2 = ProtoField.new("accel_2 (float)", "mavlink_proto.NAV_FILTER_BIAS_accel_2", ftypes.FLOAT, nil) +f.NAV_FILTER_BIAS_gyro_0 = ProtoField.new("gyro_0 (float)", "mavlink_proto.NAV_FILTER_BIAS_gyro_0", ftypes.FLOAT, nil) +f.NAV_FILTER_BIAS_gyro_1 = ProtoField.new("gyro_1 (float)", "mavlink_proto.NAV_FILTER_BIAS_gyro_1", ftypes.FLOAT, nil) +f.NAV_FILTER_BIAS_gyro_2 = ProtoField.new("gyro_2 (float)", "mavlink_proto.NAV_FILTER_BIAS_gyro_2", ftypes.FLOAT, nil) + +f.RADIO_CALIBRATION_aileron_0 = ProtoField.new("aileron[0] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_aileron_0", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_aileron_1 = ProtoField.new("aileron[1] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_aileron_1", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_aileron_2 = ProtoField.new("aileron[2] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_aileron_2", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_elevator_0 = ProtoField.new("elevator[0] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_elevator_0", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_elevator_1 = ProtoField.new("elevator[1] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_elevator_1", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_elevator_2 = ProtoField.new("elevator[2] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_elevator_2", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_rudder_0 = ProtoField.new("rudder[0] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_rudder_0", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_rudder_1 = ProtoField.new("rudder[1] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_rudder_1", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_rudder_2 = ProtoField.new("rudder[2] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_rudder_2", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_gyro_0 = ProtoField.new("gyro[0] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_gyro_0", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_gyro_1 = ProtoField.new("gyro[1] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_gyro_1", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_pitch_0 = ProtoField.new("pitch[0] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_pitch_0", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_pitch_1 = ProtoField.new("pitch[1] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_pitch_1", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_pitch_2 = ProtoField.new("pitch[2] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_pitch_2", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_pitch_3 = ProtoField.new("pitch[3] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_pitch_3", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_pitch_4 = ProtoField.new("pitch[4] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_pitch_4", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_throttle_0 = ProtoField.new("throttle[0] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_throttle_0", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_throttle_1 = ProtoField.new("throttle[1] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_throttle_1", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_throttle_2 = ProtoField.new("throttle[2] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_throttle_2", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_throttle_3 = ProtoField.new("throttle[3] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_throttle_3", ftypes.UINT16, nil) +f.RADIO_CALIBRATION_throttle_4 = ProtoField.new("throttle[4] (uint16_t)", "mavlink_proto.RADIO_CALIBRATION_throttle_4", ftypes.UINT16, nil) + +f.UALBERTA_SYS_STATUS_mode = ProtoField.new("mode (uint8_t)", "mavlink_proto.UALBERTA_SYS_STATUS_mode", ftypes.UINT8, nil) +f.UALBERTA_SYS_STATUS_nav_mode = ProtoField.new("nav_mode (uint8_t)", "mavlink_proto.UALBERTA_SYS_STATUS_nav_mode", ftypes.UINT8, nil) +f.UALBERTA_SYS_STATUS_pilot = ProtoField.new("pilot (uint8_t)", "mavlink_proto.UALBERTA_SYS_STATUS_pilot", ftypes.UINT8, nil) + f.UAVIONIX_ADSB_OUT_CFG_ICAO = ProtoField.new("ICAO (uint32_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_ICAO", ftypes.UINT32, nil) f.UAVIONIX_ADSB_OUT_CFG_callsign = ProtoField.new("callsign (char)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_callsign", ftypes.STRING, nil) f.UAVIONIX_ADSB_OUT_CFG_emitterType = ProtoField.new("emitterType (ADSB_EMITTER_TYPE)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_emitterType", ftypes.UINT8, enumEntryName.ADSB_EMITTER_TYPE) @@ -10678,25 +11631,6 @@ f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FA f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", "UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", 8, nil, 128) f.UAVIONIX_ADSB_OUT_STATUS_flight_id = ProtoField.new("flight_id (char)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_flight_id", ftypes.STRING, nil) -f.ICAROUS_HEARTBEAT_status = ProtoField.new("status (ICAROUS_FMS_STATE)", "mavlink_proto.ICAROUS_HEARTBEAT_status", ftypes.UINT8, enumEntryName.ICAROUS_FMS_STATE) - -f.ICAROUS_KINEMATIC_BANDS_numBands = ProtoField.new("numBands (int8_t)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_numBands", ftypes.INT8, nil) -f.ICAROUS_KINEMATIC_BANDS_type1 = ProtoField.new("type1 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type1", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) -f.ICAROUS_KINEMATIC_BANDS_min1 = ProtoField.new("min1 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min1", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_max1 = ProtoField.new("max1 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max1", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_type2 = ProtoField.new("type2 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type2", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) -f.ICAROUS_KINEMATIC_BANDS_min2 = ProtoField.new("min2 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min2", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_max2 = ProtoField.new("max2 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max2", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_type3 = ProtoField.new("type3 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type3", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) -f.ICAROUS_KINEMATIC_BANDS_min3 = ProtoField.new("min3 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min3", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_max3 = ProtoField.new("max3 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max3", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_type4 = ProtoField.new("type4 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type4", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) -f.ICAROUS_KINEMATIC_BANDS_min4 = ProtoField.new("min4 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min4", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_max4 = ProtoField.new("max4 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max4", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_type5 = ProtoField.new("type5 (ICAROUS_TRACK_BAND_TYPES)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_type5", ftypes.UINT8, enumEntryName.ICAROUS_TRACK_BAND_TYPES) -f.ICAROUS_KINEMATIC_BANDS_min5 = ProtoField.new("min5 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_min5", ftypes.FLOAT, nil) -f.ICAROUS_KINEMATIC_BANDS_max5 = ProtoField.new("max5 (float)", "mavlink_proto.ICAROUS_KINEMATIC_BANDS_max5", ftypes.FLOAT, nil) - f.LOWEHEISER_GOV_EFI_volt_batt = ProtoField.new("volt_batt (float)", "mavlink_proto.LOWEHEISER_GOV_EFI_volt_batt", ftypes.FLOAT, nil) f.LOWEHEISER_GOV_EFI_curr_batt = ProtoField.new("curr_batt (float)", "mavlink_proto.LOWEHEISER_GOV_EFI_curr_batt", ftypes.FLOAT, nil) f.LOWEHEISER_GOV_EFI_curr_gen = ProtoField.new("curr_gen (float)", "mavlink_proto.LOWEHEISER_GOV_EFI_curr_gen", ftypes.FLOAT, nil) @@ -10721,6 +11655,247 @@ f.LOWEHEISER_GOV_EFI_efi_index = ProtoField.new("efi_index (uint8_t)", "mavlink_ f.LOWEHEISER_GOV_EFI_generator_status = ProtoField.new("generator_status (uint16_t)", "mavlink_proto.LOWEHEISER_GOV_EFI_generator_status", ftypes.UINT16, nil) f.LOWEHEISER_GOV_EFI_efi_status = ProtoField.new("efi_status (uint16_t)", "mavlink_proto.LOWEHEISER_GOV_EFI_efi_status", ftypes.UINT16, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_target_system", ftypes.UINT8, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_target_component", ftypes.UINT8, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_time_boot_ms", ftypes.UINT32, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_flags = ProtoField.new("flags (MAV_STORM32_GIMBAL_DEVICE_FLAGS)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", 17, nil, 1) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", 17, nil, 2) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 17, nil, 4) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 17, nil, 8) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", 17, nil, 16) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", 17, nil, 256) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", 17, nil, 512) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 17, nil, 1024) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", 17, nil, 2048) +f.STORM32_GIMBAL_DEVICE_STATUS_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", 17, nil, 65536) +f.STORM32_GIMBAL_DEVICE_STATUS_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_q_0", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_q_1", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_q_2", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_q_3", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_x", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_y", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_z", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_yaw_absolute = ProtoField.new("yaw_absolute (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_yaw_absolute", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags = ProtoField.new("failure_flags (GIMBAL_DEVICE_ERROR_FLAGS)", "mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", 10, nil, 1) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", 10, nil, 2) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", 10, nil, 4) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", 10, nil, 8) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", 10, nil, 16) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", 10, nil, 32) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", 10, nil, 64) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", 10, nil, 128) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", 10, nil, 256) +f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", "GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", 10, nil, 512) + +f.STORM32_GIMBAL_DEVICE_CONTROL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_target_system", ftypes.UINT8, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_target_component", ftypes.UINT8, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags = ProtoField.new("flags (MAV_STORM32_GIMBAL_DEVICE_FLAGS)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", 17, nil, 1) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", 17, nil, 2) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 17, nil, 4) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 17, nil, 8) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", 17, nil, 16) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", 17, nil, 256) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", 17, nil, 512) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 17, nil, 1024) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", 17, nil, 2048) +f.STORM32_GIMBAL_DEVICE_CONTROL_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", 17, nil, 65536) +f.STORM32_GIMBAL_DEVICE_CONTROL_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_q_0", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_q_1", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_q_2", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_q_3", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_x", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_y", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_z", ftypes.FLOAT, nil) + +f.STORM32_GIMBAL_MANAGER_INFORMATION_gimbal_id = ProtoField.new("gimbal_id (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_gimbal_id", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags = ProtoField.new("device_cap_flags (MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags", ftypes.UINT32, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", 18, nil, 1) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", 18, nil, 2) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", 18, nil, 4) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", 18, nil, 8) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", 18, nil, 16) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", 18, nil, 32) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", 18, nil, 64) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", 18, nil, 128) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", 18, nil, 256) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", 18, nil, 512) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", 18, nil, 1024) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW", 18, nil, 2048) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW", 18, nil, 65536) +f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags.MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC", "MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC", 18, nil, 131072) +f.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags = ProtoField.new("manager_cap_flags (MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags", ftypes.UINT32, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags_flagMAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags.MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES", "MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES", 2, nil, 1) +f.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags_flagMAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags.MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE", "MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE", 2, nil, 2) +f.STORM32_GIMBAL_MANAGER_INFORMATION_roll_min = ProtoField.new("roll_min (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_roll_min", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_roll_max = ProtoField.new("roll_max (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_roll_max", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_pitch_min = ProtoField.new("pitch_min (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_pitch_min", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_pitch_max = ProtoField.new("pitch_max (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_pitch_max", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_yaw_min = ProtoField.new("yaw_min (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_yaw_min", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_INFORMATION_yaw_max", ftypes.FLOAT, nil) + +f.STORM32_GIMBAL_MANAGER_STATUS_gimbal_id = ProtoField.new("gimbal_id (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_gimbal_id", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_STATUS_supervisor = ProtoField.new("supervisor (MAV_STORM32_GIMBAL_MANAGER_CLIENT)", "mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_supervisor", ftypes.UINT8, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_CLIENT) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags = ProtoField.new("device_flags (MAV_STORM32_GIMBAL_DEVICE_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", 17, nil, 1) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", 17, nil, 2) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 17, nil, 4) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 17, nil, 8) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", 17, nil, 16) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", 17, nil, 256) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", 17, nil, 512) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 17, nil, 1024) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", 17, nil, 2048) +f.STORM32_GIMBAL_MANAGER_STATUS_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", 17, nil, 65536) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags = ProtoField.new("manager_flags (MAV_STORM32_GIMBAL_MANAGER_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", 11, nil, 1) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", 11, nil, 2) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", 11, nil, 4) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", 11, nil, 8) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", 11, nil, 16) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", 11, nil, 32) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", 11, nil, 64) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", 11, nil, 128) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", 11, nil, 256) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", 11, nil, 512) +f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", 11, nil, 1024) +f.STORM32_GIMBAL_MANAGER_STATUS_profile = ProtoField.new("profile (MAV_STORM32_GIMBAL_MANAGER_PROFILE)", "mavlink_proto.STORM32_GIMBAL_MANAGER_STATUS_profile", ftypes.UINT8, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_PROFILE) + +f.STORM32_GIMBAL_MANAGER_CONTROL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_target_system", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_target_component", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_gimbal_id = ProtoField.new("gimbal_id (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_gimbal_id", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_client = ProtoField.new("client (MAV_STORM32_GIMBAL_MANAGER_CLIENT)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_client", ftypes.UINT8, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_CLIENT) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags = ProtoField.new("device_flags (MAV_STORM32_GIMBAL_DEVICE_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", 17, nil, 1) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", 17, nil, 2) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 17, nil, 4) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 17, nil, 8) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", 17, nil, 16) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", 17, nil, 256) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", 17, nil, 512) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 17, nil, 1024) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", 17, nil, 2048) +f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", 17, nil, 65536) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags = ProtoField.new("manager_flags (MAV_STORM32_GIMBAL_MANAGER_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", 11, nil, 1) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", 11, nil, 2) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", 11, nil, 4) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", 11, nil, 8) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", 11, nil, 16) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", 11, nil, 32) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", 11, nil, 64) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", 11, nil, 128) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", 11, nil, 256) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", 11, nil, 512) +f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", 11, nil, 1024) +f.STORM32_GIMBAL_MANAGER_CONTROL_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_q_0", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_q_1", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_q_2", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_q_3", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_x", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_y", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_z", ftypes.FLOAT, nil) + +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_target_system", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_target_component", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_gimbal_id = ProtoField.new("gimbal_id (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_gimbal_id", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_client = ProtoField.new("client (MAV_STORM32_GIMBAL_MANAGER_CLIENT)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_client", ftypes.UINT8, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_CLIENT) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags = ProtoField.new("device_flags (MAV_STORM32_GIMBAL_DEVICE_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT", 17, nil, 1) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL", 17, nil, 2) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 17, nil, 4) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 17, nil, 8) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK", 17, nil, 16) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE", 17, nil, 256) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE", 17, nil, 512) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 17, nil, 1024) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED", 17, nil, 2048) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags.MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", "MAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END", 17, nil, 65536) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags = ProtoField.new("manager_flags (MAV_STORM32_GIMBAL_MANAGER_FLAGS)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags", ftypes.UINT16, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE", 11, nil, 1) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE", 11, nil, 2) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE", 11, nil, 4) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE", 11, nil, 8) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE", 11, nil, 16) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE", 11, nil, 32) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE", 11, nil, 64) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE", 11, nil, 128) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE", 11, nil, 256) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON", 11, nil, 512) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE = ProtoField.bool("mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags.MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", "MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE", 11, nil, 1024) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_pitch = ProtoField.new("pitch (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_pitch", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_yaw = ProtoField.new("yaw (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_yaw", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_pitch_rate = ProtoField.new("pitch_rate (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_pitch_rate", ftypes.FLOAT, nil) +f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_yaw_rate = ProtoField.new("yaw_rate (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_yaw_rate", ftypes.FLOAT, nil) + +f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_target_system", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_target_component", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_gimbal_id = ProtoField.new("gimbal_id (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_gimbal_id", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_client = ProtoField.new("client (MAV_STORM32_GIMBAL_MANAGER_CLIENT)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_client", ftypes.UINT8, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_CLIENT) +f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_roll = ProtoField.new("roll (float)", "mavlink_proto.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_roll", ftypes.FLOAT, nil) + +f.STORM32_GIMBAL_MANAGER_PROFILE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_target_system", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_target_component", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_gimbal_id = ProtoField.new("gimbal_id (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_gimbal_id", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_profile = ProtoField.new("profile (MAV_STORM32_GIMBAL_MANAGER_PROFILE)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_profile", ftypes.UINT8, enumEntryName.MAV_STORM32_GIMBAL_MANAGER_PROFILE) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_0 = ProtoField.new("priorities[0] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_0", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_1 = ProtoField.new("priorities[1] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_1", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_2 = ProtoField.new("priorities[2] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_2", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_3 = ProtoField.new("priorities[3] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_3", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_4 = ProtoField.new("priorities[4] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_4", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_5 = ProtoField.new("priorities[5] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_5", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_6 = ProtoField.new("priorities[6] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_6", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_7 = ProtoField.new("priorities[7] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_priorities_7", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_profile_flags = ProtoField.new("profile_flags (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_profile_flags", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_rc_timeout = ProtoField.new("rc_timeout (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_rc_timeout", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_0 = ProtoField.new("timeouts[0] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_0", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_1 = ProtoField.new("timeouts[1] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_1", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_2 = ProtoField.new("timeouts[2] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_2", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_3 = ProtoField.new("timeouts[3] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_3", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_4 = ProtoField.new("timeouts[4] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_4", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_5 = ProtoField.new("timeouts[5] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_5", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_6 = ProtoField.new("timeouts[6] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_6", ftypes.UINT8, nil) +f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_7 = ProtoField.new("timeouts[7] (uint8_t)", "mavlink_proto.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_7", ftypes.UINT8, nil) + +f.QSHOT_STATUS_mode = ProtoField.new("mode (MAV_QSHOT_MODE)", "mavlink_proto.QSHOT_STATUS_mode", ftypes.UINT16, enumEntryName.MAV_QSHOT_MODE) +f.QSHOT_STATUS_shot_state = ProtoField.new("shot_state (uint16_t)", "mavlink_proto.QSHOT_STATUS_shot_state", ftypes.UINT16, nil) + +f.COMPONENT_PREARM_STATUS_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.COMPONENT_PREARM_STATUS_target_system", ftypes.UINT8, nil) +f.COMPONENT_PREARM_STATUS_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.COMPONENT_PREARM_STATUS_target_component", ftypes.UINT8, nil) +f.COMPONENT_PREARM_STATUS_enabled_flags = ProtoField.new("enabled_flags (uint32_t)", "mavlink_proto.COMPONENT_PREARM_STATUS_enabled_flags", ftypes.UINT32, nil) +f.COMPONENT_PREARM_STATUS_fail_flags = ProtoField.new("fail_flags (uint32_t)", "mavlink_proto.COMPONENT_PREARM_STATUS_fail_flags", ftypes.UINT32, nil) + +f.AVSS_PRS_SYS_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.AVSS_PRS_SYS_STATUS_time_boot_ms", ftypes.UINT32, nil) +f.AVSS_PRS_SYS_STATUS_error_status = ProtoField.new("error_status (uint32_t)", "mavlink_proto.AVSS_PRS_SYS_STATUS_error_status", ftypes.UINT32, nil) +f.AVSS_PRS_SYS_STATUS_battery_status = ProtoField.new("battery_status (uint32_t)", "mavlink_proto.AVSS_PRS_SYS_STATUS_battery_status", ftypes.UINT32, nil) +f.AVSS_PRS_SYS_STATUS_arm_status = ProtoField.new("arm_status (uint8_t)", "mavlink_proto.AVSS_PRS_SYS_STATUS_arm_status", ftypes.UINT8, nil) +f.AVSS_PRS_SYS_STATUS_charge_status = ProtoField.new("charge_status (uint8_t)", "mavlink_proto.AVSS_PRS_SYS_STATUS_charge_status", ftypes.UINT8, nil) + +f.AVSS_DRONE_POSITION_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.AVSS_DRONE_POSITION_time_boot_ms", ftypes.UINT32, nil) +f.AVSS_DRONE_POSITION_lat = ProtoField.new("lat (int32_t)", "mavlink_proto.AVSS_DRONE_POSITION_lat", ftypes.INT32, nil) +f.AVSS_DRONE_POSITION_lon = ProtoField.new("lon (int32_t)", "mavlink_proto.AVSS_DRONE_POSITION_lon", ftypes.INT32, nil) +f.AVSS_DRONE_POSITION_alt = ProtoField.new("alt (int32_t)", "mavlink_proto.AVSS_DRONE_POSITION_alt", ftypes.INT32, nil) +f.AVSS_DRONE_POSITION_ground_alt = ProtoField.new("ground_alt (float)", "mavlink_proto.AVSS_DRONE_POSITION_ground_alt", ftypes.FLOAT, nil) +f.AVSS_DRONE_POSITION_barometer_alt = ProtoField.new("barometer_alt (float)", "mavlink_proto.AVSS_DRONE_POSITION_barometer_alt", ftypes.FLOAT, nil) + +f.AVSS_DRONE_IMU_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.AVSS_DRONE_IMU_time_boot_ms", ftypes.UINT32, nil) +f.AVSS_DRONE_IMU_q1 = ProtoField.new("q1 (float)", "mavlink_proto.AVSS_DRONE_IMU_q1", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_q2 = ProtoField.new("q2 (float)", "mavlink_proto.AVSS_DRONE_IMU_q2", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_q3 = ProtoField.new("q3 (float)", "mavlink_proto.AVSS_DRONE_IMU_q3", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_q4 = ProtoField.new("q4 (float)", "mavlink_proto.AVSS_DRONE_IMU_q4", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_xacc = ProtoField.new("xacc (float)", "mavlink_proto.AVSS_DRONE_IMU_xacc", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_yacc = ProtoField.new("yacc (float)", "mavlink_proto.AVSS_DRONE_IMU_yacc", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_zacc = ProtoField.new("zacc (float)", "mavlink_proto.AVSS_DRONE_IMU_zacc", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_xgyro = ProtoField.new("xgyro (float)", "mavlink_proto.AVSS_DRONE_IMU_xgyro", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_ygyro = ProtoField.new("ygyro (float)", "mavlink_proto.AVSS_DRONE_IMU_ygyro", ftypes.FLOAT, nil) +f.AVSS_DRONE_IMU_zgyro = ProtoField.new("zgyro (float)", "mavlink_proto.AVSS_DRONE_IMU_zgyro", ftypes.FLOAT, nil) + +f.AVSS_DRONE_OPERATION_MODE_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.AVSS_DRONE_OPERATION_MODE_time_boot_ms", ftypes.UINT32, nil) +f.AVSS_DRONE_OPERATION_MODE_M300_operation_mode = ProtoField.new("M300_operation_mode (uint8_t)", "mavlink_proto.AVSS_DRONE_OPERATION_MODE_M300_operation_mode", ftypes.UINT8, nil) +f.AVSS_DRONE_OPERATION_MODE_horsefly_operation_mode = ProtoField.new("horsefly_operation_mode (uint8_t)", "mavlink_proto.AVSS_DRONE_OPERATION_MODE_horsefly_operation_mode", ftypes.UINT8, nil) + f.CUBEPILOT_RAW_RC_rc_raw_0 = ProtoField.new("rc_raw[0] (uint8_t)", "mavlink_proto.CUBEPILOT_RAW_RC_rc_raw_0", ftypes.UINT8, nil) f.CUBEPILOT_RAW_RC_rc_raw_1 = ProtoField.new("rc_raw[1] (uint8_t)", "mavlink_proto.CUBEPILOT_RAW_RC_rc_raw_1", ftypes.UINT8, nil) f.CUBEPILOT_RAW_RC_rc_raw_2 = ProtoField.new("rc_raw[2] (uint8_t)", "mavlink_proto.CUBEPILOT_RAW_RC_rc_raw_2", ftypes.UINT8, nil) @@ -10785,21 +11960,6 @@ f.AIRLINK_AUTH_password = ProtoField.new("password (char)", "mavlink_proto.AIRLI 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) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", 8, nil, 1) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED", 8, nil, 2) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED", 8, nil, 4) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED", 8, nil, 8) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED", 8, nil, 16) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED", 8, nil, 32) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", 8, nil, 64) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED", 8, nil, 128) -f.HEARTBEAT_custom_mode = ProtoField.new("custom_mode (uint32_t)", "mavlink_proto.HEARTBEAT_custom_mode", ftypes.UINT32, nil) -f.HEARTBEAT_system_status = ProtoField.new("system_status (MAV_STATE)", "mavlink_proto.HEARTBEAT_system_status", ftypes.UINT8, enumEntryName.MAV_STATE) -f.HEARTBEAT_mavlink_version = ProtoField.new("mavlink_version (uint8_t)", "mavlink_proto.HEARTBEAT_mavlink_version", ftypes.UINT8, nil) - -- dissect flag field function dissect_flags_LIMIT_MODULE(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagLIMIT_GPSLOCK"], tvbrange, value) @@ -11181,6 +12341,53 @@ function dissect_flags_MAV_WINCH_STATUS_FLAG(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagMAV_WINCH_STATUS_CLUTCH_ENGAGED"], tvbrange, value) end -- dissect flag field +function dissect_flags_AIRSPEED_SENSOR_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagAIRSPEED_SENSOR_USING"], tvbrange, value) + tree:add_le(f[name .. "_flagAIRSPEED_SENSOR_FLAGS_ENUM_END"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_RADIO_RC_CHANNELS_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagRADIO_RC_CHANNELS_FLAGS_FAILSAFE"], tvbrange, value) + tree:add_le(f[name .. "_flagRADIO_RC_CHANNELS_FLAGS_OUTDATED"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_MODE_PROPERTY(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_PROPERTY_ADVANCED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_PROPERTY_NOT_USER_SELECTABLE"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_GPS_SYSTEM_ERROR_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_INCOMING_CORRECTIONS"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_CONFIGURATION"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_SOFTWARE"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_ANTENNA"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_EVENT_CONGESTION"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_CPU_OVERLOAD"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_OUTPUT_CONGESTION"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_MODE_FLAG(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_TEST_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_AUTO_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_GUIDED_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_STABILIZE_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_HIL_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_SAFETY_ARMED"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_MODE_FLAG_DECODE_POSITION(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_TEST"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_AUTO"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_GUIDED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_STABILIZE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_HIL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_MANUAL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_SAFETY"], tvbrange, value) +end +-- dissect flag field function dissect_flags_UAVIONIX_ADSB_OUT_DYNAMIC_STATE(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE"], tvbrange, value) tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED"], tvbrange, value) @@ -11233,26 +12440,127 @@ function dissect_flags_UAVIONIX_ADSB_OUT_STATUS_FAULT(tree, name, tvbrange, valu tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_MODE_FLAG(tree, name, tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_TEST_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_AUTO_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_GUIDED_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_STABILIZE_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_HIL_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_SAFETY_ARMED"], tvbrange, value) +function dissect_flags_MAV_STORM32_GIMBAL_PREARM_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_IS_NORMAL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_IMUS_WORKING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_MOTORS_WORKING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_ENCODERS_WORKING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_VOLTAGE_OK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_VIRTUALCHANNELS_RECEIVING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_MAVLINK_RECEIVING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_STORM32LINK_QFIX"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_STORM32LINK_WORKING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_CAMERA_CONNECTED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_AUX0_LOW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_AUX1_LOW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_PREARM_FLAGS_NTLOGGER_WORKING"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_MODE_FLAG_DECODE_POSITION(tree, name, tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_TEST"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_AUTO"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_GUIDED"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_STABILIZE"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_HIL"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_MANUAL"], tvbrange, value) - tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_SAFETY"], tvbrange, value) +function dissect_flags_MAV_STORM32_CAMERA_PREARM_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_CAMERA_PREARM_FLAGS_CONNECTED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_CAMERA_PREARM_FLAGS_ENUM_END"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_FLAGS_ENUM_END"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_STORM32_GIMBAL_MANAGER_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE"], tvbrange, value) +end +-- dissect payload of message type zVIDEO_STREAM_INFORMATION +function payload_fns.payload_26900(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 246 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 246) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_camera_id, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_status, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_framerate, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_resolution_h, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_resolution_v, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_bitrate, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_rotation, tvbrange, value) + tvbrange = padded(offset + 16, 230) + value = tvbrange:string() + subtree = tree:add_le(f.zVIDEO_STREAM_INFORMATION_uri, tvbrange, value) end -- dissect payload of message type SENSOR_OFFSETS function payload_fns.payload_150(buffer, tree, msgid, offset, limit, pinfo) @@ -17239,257 +18547,979 @@ function payload_fns.payload_11044(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_3, tvbrange, value) end --- dissect payload of message type VIDEO_STREAM_INFORMATION99 -function payload_fns.payload_26900(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT_STAMPED +function payload_fns.payload_223(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 246 > limit) then + if (offset + 47 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 246) + padded:set_size(offset + 47) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 14, 1) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_camera_id, tvbrange, value) - tvbrange = padded(offset + 15, 1) + subtree = tree:add_le(f.COMMAND_INT_STAMPED_utc_time, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_vehicle_timestamp, tvbrange, value) + tvbrange = padded(offset + 42, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_status, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_framerate, tvbrange, value) - tvbrange = padded(offset + 8, 2) + subtree = tree:add_le(f.COMMAND_INT_STAMPED_target_system, tvbrange, value) + tvbrange = padded(offset + 43, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_resolution_h, tvbrange, value) - tvbrange = padded(offset + 10, 2) + subtree = tree:add_le(f.COMMAND_INT_STAMPED_target_component, tvbrange, value) + tvbrange = padded(offset + 44, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_resolution_v, tvbrange, value) - tvbrange = padded(offset + 4, 4) + subtree = tree:add_le(f.COMMAND_INT_STAMPED_frame, tvbrange, value) + tvbrange = padded(offset + 40, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_bitrate, tvbrange, value) - tvbrange = padded(offset + 12, 2) + subtree = tree:add_le(f.COMMAND_INT_STAMPED_command, tvbrange, value) + tvbrange = padded(offset + 45, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_rotation, tvbrange, value) - tvbrange = padded(offset + 16, 230) - value = tvbrange:string() - subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_uri, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_STAMPED_current, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_autocontinue, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_param1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_param2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_param3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_param4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_x, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_y, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_STAMPED_z, tvbrange, value) end --- dissect payload of message type SYS_STATUS -function payload_fns.payload_1(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG_STAMPED +function payload_fns.payload_224(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 31 > limit) then + if (offset + 45 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 31) + padded:set_size(offset + 45) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_present, tvbrange, value) - dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_present", tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_enabled, tvbrange, value) - dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_enabled", tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_health, tvbrange, value) - dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_health", tvbrange, value) - tvbrange = padded(offset + 12, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_load, tvbrange, value) - tvbrange = padded(offset + 14, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_voltage_battery, tvbrange, value) - tvbrange = padded(offset + 16, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.SYS_STATUS_current_battery, tvbrange, value) - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_int() - subtree = tree:add_le(f.SYS_STATUS_battery_remaining, tvbrange, value) - tvbrange = padded(offset + 18, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_drop_rate_comm, tvbrange, value) - tvbrange = padded(offset + 20, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_errors_comm, tvbrange, value) - tvbrange = padded(offset + 22, 2) + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_utc_time, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_vehicle_timestamp, tvbrange, value) + tvbrange = padded(offset + 42, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_errors_count1, tvbrange, value) - tvbrange = padded(offset + 24, 2) + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_target_system, tvbrange, value) + tvbrange = padded(offset + 43, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_errors_count2, tvbrange, value) - tvbrange = padded(offset + 26, 2) + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_target_component, tvbrange, value) + tvbrange = padded(offset + 40, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_errors_count3, tvbrange, value) - tvbrange = padded(offset + 28, 2) + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_command, tvbrange, value) + tvbrange = padded(offset + 44, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SYS_STATUS_errors_count4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_confirmation, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param5, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param6, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_STAMPED_param7, tvbrange, value) end --- dissect payload of message type SYSTEM_TIME -function payload_fns.payload_2(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type SENS_POWER +function payload_fns.payload_8002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 12 > limit) then + if (offset + 16 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 12) + padded:set_size(offset + 16) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.SYSTEM_TIME_time_unix_usec, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_adc121_vspb_volt, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_adc121_cspb_amp, tvbrange, value) tvbrange = padded(offset + 8, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SYSTEM_TIME_time_boot_ms, tvbrange, value) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_adc121_cs1_amp, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_adc121_cs2_amp, tvbrange, value) end --- dissect payload of message type PING -function payload_fns.payload_4(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type SENS_MPPT +function payload_fns.payload_8003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 14 > limit) then + if (offset + 41 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 14) + padded:set_size(offset + 41) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 0, 8) value = tvbrange:le_uint64() - subtree = tree:add_le(f.PING_time_usec, tvbrange, value) + subtree = tree:add_le(f.SENS_MPPT_mppt_timestamp, tvbrange, value) tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_MPPT_mppt1_volt, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_MPPT_mppt1_amp, tvbrange, value) + tvbrange = padded(offset + 32, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.PING_seq, tvbrange, value) - tvbrange = padded(offset + 12, 1) + subtree = tree:add_le(f.SENS_MPPT_mppt1_pwm, tvbrange, value) + tvbrange = padded(offset + 38, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.PING_target_system, tvbrange, value) - tvbrange = padded(offset + 13, 1) + subtree = tree:add_le(f.SENS_MPPT_mppt1_status, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_MPPT_mppt2_volt, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_MPPT_mppt2_amp, tvbrange, value) + tvbrange = padded(offset + 34, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.PING_target_component, tvbrange, value) -end --- dissect payload of message type CHANGE_OPERATOR_CONTROL -function payload_fns.payload_5(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 28 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 28) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 0, 1) + subtree = tree:add_le(f.SENS_MPPT_mppt2_pwm, tvbrange, value) + tvbrange = padded(offset + 39, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_target_system, tvbrange, value) - tvbrange = padded(offset + 1, 1) + subtree = tree:add_le(f.SENS_MPPT_mppt2_status, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_MPPT_mppt3_volt, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_MPPT_mppt3_amp, tvbrange, value) + tvbrange = padded(offset + 36, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_control_request, tvbrange, value) - tvbrange = padded(offset + 2, 1) + subtree = tree:add_le(f.SENS_MPPT_mppt3_pwm, tvbrange, value) + tvbrange = padded(offset + 40, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_version, tvbrange, value) - tvbrange = padded(offset + 3, 25) - value = tvbrange:string() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_passkey, tvbrange, value) + subtree = tree:add_le(f.SENS_MPPT_mppt3_status, tvbrange, value) end --- dissect payload of message type CHANGE_OPERATOR_CONTROL_ACK -function payload_fns.payload_6(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type ASLCTRL_DATA +function payload_fns.payload_8004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 3 > limit) then + if (offset + 98 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 3) + padded:set_size(offset + 98) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_gcs_system_id, tvbrange, value) - tvbrange = padded(offset + 1, 1) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ASLCTRL_DATA_timestamp, tvbrange, value) + tvbrange = padded(offset + 96, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_control_request, tvbrange, value) - tvbrange = padded(offset + 2, 1) + subtree = tree:add_le(f.ASLCTRL_DATA_aslctrl_mode, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_h, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_hRef, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_hRef_t, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_PitchAngle, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_PitchAngleRef, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_q, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_qRef, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_uElev, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_uThrot, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_uThrot2, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_nZ, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_AirspeedRef, tvbrange, value) + tvbrange = padded(offset + 97, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_ack, tvbrange, value) + subtree = tree:add_le(f.ASLCTRL_DATA_SpoilersEngaged, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_YawAngle, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_YawAngleRef, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_RollAngle, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_RollAngleRef, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_p, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_pRef, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_r, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_rRef, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_uAil, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DATA_uRud, tvbrange, value) end --- dissect payload of message type AUTH_KEY -function payload_fns.payload_7(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type ASLCTRL_DEBUG +function payload_fns.payload_8005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 32 > limit) then + if (offset + 38 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 32) + padded:set_size(offset + 38) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 32) - value = tvbrange:string() - subtree = tree:add_le(f.AUTH_KEY_key, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLCTRL_DEBUG_i32_1, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLCTRL_DEBUG_i8_1, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLCTRL_DEBUG_i8_2, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_4, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_5, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_6, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_7, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLCTRL_DEBUG_f_8, tvbrange, value) end --- dissect payload of message type SET_MODE -function payload_fns.payload_11(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type ASLUAV_STATUS +function payload_fns.payload_8006(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 6 > limit) then + if (offset + 14 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 6) + padded:set_size(offset + 14) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 4, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_MODE_target_system, tvbrange, value) + subtree = tree:add_le(f.ASLUAV_STATUS_LED_status, tvbrange, value) tvbrange = padded(offset + 5, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_MODE_base_mode, tvbrange, value) - tvbrange = padded(offset + 0, 4) + subtree = tree:add_le(f.ASLUAV_STATUS_SATCOM_status, tvbrange, value) + tvbrange = padded(offset + 6, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_MODE_custom_mode, tvbrange, value) + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_0, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_1, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_2, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_3, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_4, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_5, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_6, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ASLUAV_STATUS_Servo_status_7, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASLUAV_STATUS_Motor_rpm, tvbrange, value) end --- dissect payload of message type PARAM_REQUEST_READ -function payload_fns.payload_20(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type EKF_EXT +function payload_fns.payload_8007(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 20 > limit) then + if (offset + 32 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 20) + padded:set_size(offset + 32) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 2, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.PARAM_REQUEST_READ_target_system, tvbrange, value) - tvbrange = padded(offset + 3, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.PARAM_REQUEST_READ_target_component, tvbrange, value) - tvbrange = padded(offset + 4, 16) - value = tvbrange:string() - subtree = tree:add_le(f.PARAM_REQUEST_READ_param_id, tvbrange, value) - tvbrange = padded(offset + 0, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.PARAM_REQUEST_READ_param_index, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.EKF_EXT_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_EXT_Windspeed, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_EXT_WindDir, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_EXT_WindZ, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_EXT_Airspeed, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_EXT_beta, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_EXT_alpha, tvbrange, value) end --- dissect payload of message type PARAM_REQUEST_LIST -function payload_fns.payload_21(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type ASL_OBCTRL +function payload_fns.payload_8008(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 2 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 2) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.PARAM_REQUEST_LIST_target_system, tvbrange, value) - tvbrange = padded(offset + 1, 1) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ASL_OBCTRL_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASL_OBCTRL_uElev, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASL_OBCTRL_uThrot, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASL_OBCTRL_uThrot2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASL_OBCTRL_uAilL, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASL_OBCTRL_uAilR, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ASL_OBCTRL_uRud, tvbrange, value) + tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.PARAM_REQUEST_LIST_target_component, tvbrange, value) + subtree = tree:add_le(f.ASL_OBCTRL_obctrl_status, tvbrange, value) end --- dissect payload of message type PARAM_VALUE -function payload_fns.payload_22(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type SENS_ATMOS +function payload_fns.payload_8009(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 25 > limit) then + if (offset + 16 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 25) + padded:set_size(offset + 16) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SENS_ATMOS_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_ATMOS_TempAmbient, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_ATMOS_Humidity, tvbrange, value) +end +-- dissect payload of message type SENS_BATMON +function payload_fns.payload_8010(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 41 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 41) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SENS_BATMON_batmon_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_BATMON_temperature, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_voltage, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SENS_BATMON_current, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_SoC, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_batterystatus, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_serialnumber, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_safetystatus, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_operationstatus, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_cellvoltage1, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_cellvoltage2, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_cellvoltage3, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_cellvoltage4, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_cellvoltage5, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_BATMON_cellvoltage6, tvbrange, value) +end +-- dissect payload of message type FW_SOARING_DATA +function payload_fns.payload_8011(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 102 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 102) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FW_SOARING_DATA_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FW_SOARING_DATA_timestampModeChanged, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_xW, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_xR, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_xLat, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_xLon, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_VarW, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_VarR, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_VarLat, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_VarLon, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_LoiterRadius, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_LoiterDirection, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_DistToSoarPoint, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_vSinkExp, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_z1_LocalUpdraftSpeed, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_z2_DeltaRoll, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_z1_exp, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_z2_exp, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_ThermalGSNorth, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_ThermalGSEast, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_TSE_dot, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_DebugVar1, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FW_SOARING_DATA_DebugVar2, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FW_SOARING_DATA_ControlMode, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FW_SOARING_DATA_valid, tvbrange, value) +end +-- dissect payload of message type SENSORPOD_STATUS +function payload_fns.payload_8012(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 16 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 16) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SENSORPOD_STATUS_timestamp, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_visensor_rate_1, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_visensor_rate_2, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_visensor_rate_3, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_visensor_rate_4, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_recording_nodes_count, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_cpu_temp, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSORPOD_STATUS_free_space, tvbrange, value) +end +-- dissect payload of message type SENS_POWER_BOARD +function payload_fns.payload_8013(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 46 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 46) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SENS_POWER_BOARD_timestamp, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_status, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_led_status, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_system_volt, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_servo_volt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_digital_volt, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_mot_l_amp, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_mot_r_amp, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_analog_amp, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_digital_amp, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_ext_amp, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENS_POWER_BOARD_pwr_brd_aux_amp, tvbrange, value) +end +-- dissect payload of message type GSM_LINK_STATUS +function payload_fns.payload_8014(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 14 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 14) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GSM_LINK_STATUS_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GSM_LINK_STATUS_gsm_modem_type, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GSM_LINK_STATUS_gsm_link_type, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GSM_LINK_STATUS_rssi, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GSM_LINK_STATUS_rsrp_rscp, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GSM_LINK_STATUS_sinr_ecio, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GSM_LINK_STATUS_rsrq, tvbrange, value) +end +-- dissect payload of message type SATCOM_LINK_STATUS +function payload_fns.payload_8015(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 24 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 24) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_last_heartbeat, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_failed_sessions, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_successful_sessions, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_signal_quality, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_ring_pending, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_tx_session_pending, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SATCOM_LINK_STATUS_rx_session_pending, tvbrange, value) +end +-- dissect payload of message type SENSOR_AIRFLOW_ANGLES +function payload_fns.payload_8016(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 18 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 18) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SENSOR_AIRFLOW_ANGLES_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_AIRFLOW_ANGLES_angleofattack, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSOR_AIRFLOW_ANGLES_angleofattack_valid, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_AIRFLOW_ANGLES_sideslip, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SENSOR_AIRFLOW_ANGLES_sideslip_valid, tvbrange, value) +end +-- dissect payload of message type SYS_STATUS +function payload_fns.payload_1(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 31 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 31) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_present, tvbrange, value) + dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_present", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_enabled, tvbrange, value) + dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_enabled", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_health, tvbrange, value) + dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_health", tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_load, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_voltage_battery, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SYS_STATUS_current_battery, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.SYS_STATUS_battery_remaining, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_drop_rate_comm, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_comm, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count1, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count2, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count3, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count4, tvbrange, value) +end +-- dissect payload of message type SYSTEM_TIME +function payload_fns.payload_2(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 12 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 12) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SYSTEM_TIME_time_unix_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYSTEM_TIME_time_boot_ms, tvbrange, value) +end +-- dissect payload of message type PING +function payload_fns.payload_4(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 14 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 14) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.PING_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PING_seq, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PING_target_system, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PING_target_component, tvbrange, value) +end +-- dissect payload of message type CHANGE_OPERATOR_CONTROL +function payload_fns.payload_5(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 28 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 28) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_control_request, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_version, tvbrange, value) + tvbrange = padded(offset + 3, 25) + value = tvbrange:string() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_passkey, tvbrange, value) +end +-- dissect payload of message type CHANGE_OPERATOR_CONTROL_ACK +function payload_fns.payload_6(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 3 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 3) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_gcs_system_id, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_control_request, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_ack, tvbrange, value) +end +-- dissect payload of message type AUTH_KEY +function payload_fns.payload_7(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 32 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 32) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 32) + value = tvbrange:string() + subtree = tree:add_le(f.AUTH_KEY_key, tvbrange, value) +end +-- dissect payload of message type SET_MODE +function payload_fns.payload_11(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 6 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 6) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MODE_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MODE_base_mode, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MODE_custom_mode, tvbrange, value) +end +-- dissect payload of message type PARAM_REQUEST_READ +function payload_fns.payload_20(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 20 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 20) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_READ_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_READ_target_component, tvbrange, value) + tvbrange = padded(offset + 4, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_REQUEST_READ_param_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.PARAM_REQUEST_READ_param_index, tvbrange, value) +end +-- dissect payload of message type PARAM_REQUEST_LIST +function payload_fns.payload_21(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 2 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 2) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_LIST_target_component, tvbrange, value) +end +-- dissect payload of message type PARAM_VALUE +function payload_fns.payload_22(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 25 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 25) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -23718,6 +25748,56 @@ function payload_fns.payload_75_cmd260(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_STANDARD_MODE +function payload_fns.payload_75_cmd262(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 + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_STANDARD_MODE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) +end -- dissect payload of message type COMMAND_INT with command MAV_CMD_MISSION_START function payload_fns.payload_75_cmd300(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -24918,6 +26998,56 @@ function payload_fns.payload_75_cmd601(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_SYS_CMP_ID +function payload_fns.payload_75_cmd610(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 + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) +end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW function payload_fns.payload_75_cmd1000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -27469,8 +29599,8 @@ function payload_fns.payload_75_cmd32000(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_POWER_OFF_INITIATED -function payload_fns.payload_75_cmd42000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_RESET_MPPT +function payload_fns.payload_75_cmd40001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27519,8 +29649,8 @@ function payload_fns.payload_75_cmd42000(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_FLY_CLICK -function payload_fns.payload_75_cmd42001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PAYLOAD_CONTROL +function payload_fns.payload_75_cmd40002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27569,8 +29699,8 @@ function payload_fns.payload_75_cmd42001(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_FLY_HOLD -function payload_fns.payload_75_cmd42002(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_POWER_OFF_INITIATED +function payload_fns.payload_75_cmd42000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27599,7 +29729,7 @@ function payload_fns.payload_75_cmd42002(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -27619,8 +29749,8 @@ function payload_fns.payload_75_cmd42002(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_PAUSE_CLICK -function payload_fns.payload_75_cmd42003(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_FLY_CLICK +function payload_fns.payload_75_cmd42001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27649,7 +29779,7 @@ function payload_fns.payload_75_cmd42003(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -27669,58 +29799,8 @@ function payload_fns.payload_75_cmd42003(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL -function payload_fns.payload_75_cmd42004(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 + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) - tvbrange = padded(offset + 33, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) - tvbrange = padded(offset + 34, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) -end --- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL_FIELD -function payload_fns.payload_75_cmd42005(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_FLY_HOLD +function payload_fns.payload_75_cmd42002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27749,13 +29829,13 @@ function payload_fns.payload_75_cmd42005(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) @@ -27769,58 +29849,8 @@ function payload_fns.payload_75_cmd42005(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL_YAW -function payload_fns.payload_75_cmd42006(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 + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) - tvbrange = padded(offset + 33, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) - tvbrange = padded(offset + 34, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) -end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_EKF_SOURCE_SET -function payload_fns.payload_75_cmd42007(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_PAUSE_CLICK +function payload_fns.payload_75_cmd42003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27849,7 +29879,7 @@ function payload_fns.payload_75_cmd42007(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -27869,8 +29899,8 @@ function payload_fns.payload_75_cmd42007(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_START_MAG_CAL -function payload_fns.payload_75_cmd42424(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL +function payload_fns.payload_75_cmd42004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27899,19 +29929,19 @@ function payload_fns.payload_75_cmd42424(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) @@ -27919,8 +29949,8 @@ function payload_fns.payload_75_cmd42424(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_ACCEPT_MAG_CAL -function payload_fns.payload_75_cmd42425(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL_FIELD +function payload_fns.payload_75_cmd42005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27949,13 +29979,13 @@ function payload_fns.payload_75_cmd42425(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) @@ -27969,8 +29999,8 @@ function payload_fns.payload_75_cmd42425(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_CANCEL_MAG_CAL -function payload_fns.payload_75_cmd42426(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL_YAW +function payload_fns.payload_75_cmd42006(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -27999,16 +30029,16 @@ function payload_fns.payload_75_cmd42426(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_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_FIXED_MAG_CAL_YAW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) @@ -28019,8 +30049,8 @@ function payload_fns.payload_75_cmd42426(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_FACTORY_TEST_MODE -function payload_fns.payload_75_cmd42427(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_EKF_SOURCE_SET +function payload_fns.payload_75_cmd42007(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28049,7 +30079,7 @@ function payload_fns.payload_75_cmd42427(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -28069,8 +30099,8 @@ function payload_fns.payload_75_cmd42427(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SEND_BANNER -function payload_fns.payload_75_cmd42428(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_START_MAG_CAL +function payload_fns.payload_75_cmd42424(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28099,19 +30129,19 @@ function payload_fns.payload_75_cmd42428(buffer, tree, msgid, offset, limit, pin 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_DO_START_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_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_START_MAG_CAL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) @@ -28119,8 +30149,8 @@ function payload_fns.payload_75_cmd42428(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_ACCELCAL_VEHICLE_POS -function payload_fns.payload_75_cmd42429(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_ACCEPT_MAG_CAL +function payload_fns.payload_75_cmd42425(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28149,7 +30179,7 @@ function payload_fns.payload_75_cmd42429(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -28169,8 +30199,8 @@ function payload_fns.payload_75_cmd42429(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_RESET -function payload_fns.payload_75_cmd42501(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_CANCEL_MAG_CAL +function payload_fns.payload_75_cmd42426(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28199,7 +30229,7 @@ function payload_fns.payload_75_cmd42501(buffer, tree, msgid, offset, limit, pin 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_DO_CANCEL_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -28219,8 +30249,8 @@ function payload_fns.payload_75_cmd42501(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS -function payload_fns.payload_75_cmd42502(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_FACTORY_TEST_MODE +function payload_fns.payload_75_cmd42427(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28249,13 +30279,13 @@ function payload_fns.payload_75_cmd42502(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) @@ -28269,8 +30299,8 @@ function payload_fns.payload_75_cmd42502(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION -function payload_fns.payload_75_cmd42503(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SEND_BANNER +function payload_fns.payload_75_cmd42428(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28319,8 +30349,8 @@ function payload_fns.payload_75_cmd42503(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_FULL_RESET -function payload_fns.payload_75_cmd42505(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_ACCELCAL_VEHICLE_POS +function payload_fns.payload_75_cmd42429(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28349,7 +30379,7 @@ function payload_fns.payload_75_cmd42505(buffer, tree, msgid, offset, limit, pin 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_ACCELCAL_VEHICLE_POS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) @@ -28369,58 +30399,8 @@ function payload_fns.payload_75_cmd42505(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_WINCH -function payload_fns.payload_75_cmd42600(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 + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) - tvbrange = padded(offset + 33, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) - tvbrange = padded(offset + 34, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) -end --- dissect payload of message type COMMAND_INT with command MAV_CMD_FLASH_BOOTLOADER -function payload_fns.payload_75_cmd42650(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_RESET +function payload_fns.payload_75_cmd42501(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28461,7 +30441,7 @@ function payload_fns.payload_75_cmd42650(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) @@ -28469,8 +30449,8 @@ function payload_fns.payload_75_cmd42650(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_BATTERY_RESET -function payload_fns.payload_75_cmd42651(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS +function payload_fns.payload_75_cmd42502(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28499,13 +30479,13 @@ function payload_fns.payload_75_cmd42651(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) @@ -28519,8 +30499,8 @@ function payload_fns.payload_75_cmd42651(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_DEBUG_TRAP -function payload_fns.payload_75_cmd42700(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION +function payload_fns.payload_75_cmd42503(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28569,8 +30549,8 @@ function payload_fns.payload_75_cmd42700(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SCRIPTING -function payload_fns.payload_75_cmd42701(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_FULL_RESET +function payload_fns.payload_75_cmd42505(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28619,108 +30599,8 @@ function payload_fns.payload_75_cmd42701(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_SCRIPT_TIME -function payload_fns.payload_75_cmd42702(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 + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) - tvbrange = padded(offset + 33, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) - tvbrange = padded(offset + 34, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) -end --- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_ATTITUDE_TIME -function payload_fns.payload_75_cmd42703(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 + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) - tvbrange = padded(offset + 33, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) - tvbrange = padded(offset + 34, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) -end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_SPEED -function payload_fns.payload_75_cmd43000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_WINCH +function payload_fns.payload_75_cmd42600(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28749,16 +30629,16 @@ function payload_fns.payload_75_cmd43000(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_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_WINCH_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) @@ -28769,8 +30649,8 @@ function payload_fns.payload_75_cmd43000(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_ALTITUDE -function payload_fns.payload_75_cmd43001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_FLASH_BOOTLOADER +function payload_fns.payload_75_cmd42650(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28805,22 +30685,22 @@ function payload_fns.payload_75_cmd43001(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_HEADING -function payload_fns.payload_75_cmd43002(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_BATTERY_RESET +function payload_fns.payload_75_cmd42651(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28849,13 +30729,13 @@ function payload_fns.payload_75_cmd43002(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) @@ -28869,8 +30749,8 @@ function payload_fns.payload_75_cmd43002(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_EXTERNAL_POSITION_ESTIMATE -function payload_fns.payload_75_cmd43003(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DEBUG_TRAP +function payload_fns.payload_75_cmd42700(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28899,28 +30779,28 @@ function payload_fns.payload_75_cmd43003(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_HAGL -function payload_fns.payload_75_cmd43005(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SCRIPTING +function payload_fns.payload_75_cmd42701(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28949,13 +30829,13 @@ function payload_fns.payload_75_cmd43005(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) @@ -28969,8 +30849,8 @@ function payload_fns.payload_75_cmd43005(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT with command MAV_CMD_ENUM_END -function payload_fns.payload_75_cmd43006(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_SCRIPT_TIME +function payload_fns.payload_75_cmd42702(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -28999,28 +30879,28 @@ function payload_fns.payload_75_cmd43006(buffer, tree, msgid, offset, limit, pin 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_NAV_SCRIPT_TIME_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_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_NAV_SCRIPT_TIME_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_INT -function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_ATTITUDE_TIME +function payload_fns.payload_75_cmd42703(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() @@ -29029,16 +30909,6 @@ function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - local cmd_id = padded(offset + 28, 2):le_uint() - local cmd_name = enumEntryName.MAV_CMD[cmd_id] - if cmd_name ~= nil then - pinfo.cols.info:append(": " .. cmd_name) - end - local cmd_fn = payload_fns["payload_75_cmd" .. tostring(cmd_id)] - if cmd_fn ~= nil then - cmd_fn(buffer, tree, msgid, offset, limit, pinfo) - return - end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) @@ -29059,19 +30929,19 @@ function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) 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_NAV_ATTITUDE_TIME_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_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_NAV_ATTITUDE_TIME_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_int() subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) @@ -29079,844 +30949,971 @@ function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_WAYPOINT -function payload_fns.payload_76_cmd16(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_SPEED +function payload_fns.payload_75_cmd43000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_UNLIM -function payload_fns.payload_76_cmd17(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_ALTITUDE +function payload_fns.payload_75_cmd43001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + 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_LONG_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TURNS -function payload_fns.payload_76_cmd18(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_HEADING +function payload_fns.payload_75_cmd43002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_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.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TIME -function payload_fns.payload_76_cmd19(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_EXTERNAL_POSITION_ESTIMATE +function payload_fns.payload_75_cmd43003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_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.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_RETURN_TO_LAUNCH -function payload_fns.payload_76_cmd20(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_EXTERNAL_WIND_ESTIMATE +function payload_fns.payload_75_cmd43004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + 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_LONG_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_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_EXTERNAL_WIND_ESTIMATE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAND -function payload_fns.payload_76_cmd21(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_HAGL +function payload_fns.payload_75_cmd43005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_TAKEOFF -function payload_fns.payload_76_cmd22(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW +function payload_fns.payload_75_cmd60002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5", tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6", tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAND_LOCAL -function payload_fns.payload_76_cmd23(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP +function payload_fns.payload_75_cmd60010(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS(subtree, "cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2", tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_TAKEOFF_LOCAL -function payload_fns.payload_76_cmd24(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_STORM32_DO_GIMBAL_ACTION +function payload_fns.payload_75_cmd60011(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FOLLOW -function payload_fns.payload_76_cmd25(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_QSHOT_DO_CONFIGURE +function payload_fns.payload_75_cmd60020(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT -function payload_fns.payload_76_cmd30(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_SET_ARM +function payload_fns.payload_75_cmd60050(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PRS_SET_ARM_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_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.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TO_ALT -function payload_fns.payload_76_cmd31(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_GET_ARM +function payload_fns.payload_75_cmd60051(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + 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) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FOLLOW -function payload_fns.payload_76_cmd32(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_GET_BATTERY +function payload_fns.payload_75_cmd60052(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FOLLOW_REPOSITION -function payload_fns.payload_76_cmd33(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_GET_ERR +function payload_fns.payload_75_cmd60053(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ROI -function payload_fns.payload_76_cmd80(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_SET_ARM_ALTI +function payload_fns.payload_75_cmd60070(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PRS_SET_ARM_ALTI_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_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.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_PATHPLANNING -function payload_fns.payload_76_cmd81(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_GET_ARM_ALTI +function payload_fns.payload_75_cmd60071(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SPLINE_WAYPOINT -function payload_fns.payload_76_cmd82(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_PRS_SHUTDOWN +function payload_fns.payload_75_cmd60072(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_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.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ALTITUDE_WAIT -function payload_fns.payload_76_cmd83(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT with command MAV_CMD_ENUM_END +function payload_fns.payload_75_cmd60073(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_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.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_VTOL_TAKEOFF -function payload_fns.payload_76_cmd84(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_INT +function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then + if (offset + 35 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) + padded:set_size(offset + 35) padded = padded:tvb("Untruncated payload") else padded = buffer end + local cmd_id = padded(offset + 28, 2):le_uint() + local cmd_name = enumEntryName.MAV_CMD[cmd_id] + if cmd_name ~= nil then + pinfo.cols.info:append(": " .. cmd_name) + end + local cmd_fn = payload_fns["payload_75_cmd" .. tostring(cmd_id)] + if cmd_fn ~= nil then + cmd_fn(buffer, tree, msgid, offset, limit, pinfo) + return + end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + 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_LONG_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param5, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param6, tvbrange, value) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_VTOL_LAND -function payload_fns.payload_76_cmd85(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_WAYPOINT +function payload_fns.payload_76_cmd16(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -29939,28 +31936,28 @@ function payload_fns.payload_76_cmd85(buffer, tree, msgid, offset, limit, pinfo) 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_NAV_WAYPOINT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_GUIDED_ENABLE -function payload_fns.payload_76_cmd92(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_UNLIM +function payload_fns.payload_76_cmd17(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -29983,28 +31980,28 @@ function payload_fns.payload_76_cmd92(buffer, tree, msgid, offset, limit, pinfo) subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_GUIDED_ENABLE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_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_NAV_LOITER_UNLIM_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_DELAY -function payload_fns.payload_76_cmd93(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TURNS +function payload_fns.payload_76_cmd18(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30027,28 +32024,28 @@ function payload_fns.payload_76_cmd93(buffer, tree, msgid, offset, limit, pinfo) subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_PAYLOAD_PLACE -function payload_fns.payload_76_cmd94(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TIME +function payload_fns.payload_76_cmd19(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30071,28 +32068,28 @@ function payload_fns.payload_76_cmd94(buffer, tree, msgid, offset, limit, pinfo) subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAST -function payload_fns.payload_76_cmd95(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_RETURN_TO_LAUNCH +function payload_fns.payload_76_cmd20(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30135,8 +32132,8 @@ function payload_fns.payload_76_cmd95(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_DELAY -function payload_fns.payload_76_cmd112(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAND +function payload_fns.payload_76_cmd21(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30159,28 +32156,28 @@ function payload_fns.payload_76_cmd112(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DELAY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_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_NAV_LAND_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_CHANGE_ALT -function payload_fns.payload_76_cmd113(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_TAKEOFF +function payload_fns.payload_76_cmd22(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30203,7 +32200,7 @@ function payload_fns.payload_76_cmd113(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -30212,19 +32209,19 @@ function payload_fns.payload_76_cmd113(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_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_NAV_TAKEOFF_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_DISTANCE -function payload_fns.payload_76_cmd114(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAND_LOCAL +function payload_fns.payload_76_cmd23(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30247,28 +32244,28 @@ function payload_fns.payload_76_cmd114(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DISTANCE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_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_NAV_LAND_LOCAL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_YAW -function payload_fns.payload_76_cmd115(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_TAKEOFF_LOCAL +function payload_fns.payload_76_cmd24(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30291,28 +32288,28 @@ function payload_fns.payload_76_cmd115(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_LAST -function payload_fns.payload_76_cmd159(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FOLLOW +function payload_fns.payload_76_cmd25(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30335,28 +32332,28 @@ function payload_fns.payload_76_cmd159(buffer, tree, msgid, offset, limit, pinfo 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_NAV_FOLLOW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_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_NAV_FOLLOW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_MODE -function payload_fns.payload_76_cmd176(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT +function payload_fns.payload_76_cmd30(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30379,13 +32376,13 @@ function payload_fns.payload_76_cmd176(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -30397,10 +32394,10 @@ function payload_fns.payload_76_cmd176(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_JUMP -function payload_fns.payload_76_cmd177(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TO_ALT +function payload_fns.payload_76_cmd31(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30423,28 +32420,28 @@ function payload_fns.payload_76_cmd177(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_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_NAV_LOITER_TO_ALT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CHANGE_SPEED -function payload_fns.payload_76_cmd178(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FOLLOW +function payload_fns.payload_76_cmd32(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30467,28 +32464,28 @@ function payload_fns.payload_76_cmd178(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_HOME -function payload_fns.payload_76_cmd179(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FOLLOW_REPOSITION +function payload_fns.payload_76_cmd33(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30511,28 +32508,72 @@ function payload_fns.payload_76_cmd179(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ROI +function payload_fns.payload_76_cmd80(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_PARAMETER -function payload_fns.payload_76_cmd180(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_PATHPLANNING +function payload_fns.payload_76_cmd81(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30555,28 +32596,28 @@ function payload_fns.payload_76_cmd180(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_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_NAV_PATHPLANNING_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_RELAY -function payload_fns.payload_76_cmd181(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SPLINE_WAYPOINT +function payload_fns.payload_76_cmd82(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30599,10 +32640,10 @@ function payload_fns.payload_76_cmd181(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -30611,16 +32652,16 @@ function payload_fns.payload_76_cmd181(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPEAT_RELAY -function payload_fns.payload_76_cmd182(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ALTITUDE_WAIT +function payload_fns.payload_76_cmd83(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30643,13 +32684,13 @@ function payload_fns.payload_76_cmd182(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -30663,8 +32704,8 @@ function payload_fns.payload_76_cmd182(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_SERVO -function payload_fns.payload_76_cmd183(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_VTOL_TAKEOFF +function payload_fns.payload_76_cmd84(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30687,28 +32728,28 @@ function payload_fns.payload_76_cmd183(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_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_NAV_VTOL_TAKEOFF_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPEAT_SERVO -function payload_fns.payload_76_cmd184(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_VTOL_LAND +function payload_fns.payload_76_cmd85(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30731,28 +32772,28 @@ function payload_fns.payload_76_cmd184(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FLIGHTTERMINATION -function payload_fns.payload_76_cmd185(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_GUIDED_ENABLE +function payload_fns.payload_76_cmd92(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30775,7 +32816,7 @@ function payload_fns.payload_76_cmd185(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FLIGHTTERMINATION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_GUIDED_ENABLE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -30795,8 +32836,8 @@ function payload_fns.payload_76_cmd185(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CHANGE_ALTITUDE -function payload_fns.payload_76_cmd186(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_DELAY +function payload_fns.payload_76_cmd93(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30819,16 +32860,16 @@ function payload_fns.payload_76_cmd186(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_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_NAV_DELAY_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -30839,8 +32880,8 @@ function payload_fns.payload_76_cmd186(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_RETURN_PATH_START -function payload_fns.payload_76_cmd188(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_PAYLOAD_PLACE +function payload_fns.payload_76_cmd94(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30863,7 +32904,7 @@ function payload_fns.payload_76_cmd188(buffer, tree, msgid, offset, limit, pinfo 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_NAV_PAYLOAD_PLACE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -30875,16 +32916,16 @@ function payload_fns.payload_76_cmd188(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_RETURN_PATH_START_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_RETURN_PATH_START_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_RETURN_PATH_START_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_LAND_START -function payload_fns.payload_76_cmd189(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAST +function payload_fns.payload_76_cmd95(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30919,16 +32960,16 @@ function payload_fns.payload_76_cmd189(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_RALLY_LAND -function payload_fns.payload_76_cmd190(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_DELAY +function payload_fns.payload_76_cmd112(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30951,10 +32992,10 @@ function payload_fns.payload_76_cmd190(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DELAY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -30971,8 +33012,8 @@ function payload_fns.payload_76_cmd190(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GO_AROUND -function payload_fns.payload_76_cmd191(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_CHANGE_ALT +function payload_fns.payload_76_cmd113(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -30995,7 +33036,51 @@ function payload_fns.payload_76_cmd191(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GO_AROUND_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_DISTANCE +function payload_fns.payload_76_cmd114(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DISTANCE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -31015,8 +33100,8 @@ function payload_fns.payload_76_cmd191(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPOSITION -function payload_fns.payload_76_cmd192(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_YAW +function payload_fns.payload_76_cmd115(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31039,29 +33124,28 @@ function payload_fns.payload_76_cmd192(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param2, tvbrange, value) - dissect_flags_MAV_DO_REPOSITION_FLAGS(subtree, "cmd_MAV_CMD_DO_REPOSITION_param2", tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_PAUSE_CONTINUE -function payload_fns.payload_76_cmd193(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_LAST +function payload_fns.payload_76_cmd159(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31084,7 +33168,7 @@ function payload_fns.payload_76_cmd193(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_PAUSE_CONTINUE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -31104,8 +33188,8 @@ function payload_fns.payload_76_cmd193(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_REVERSE -function payload_fns.payload_76_cmd194(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_MODE +function payload_fns.payload_76_cmd176(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31128,13 +33212,13 @@ function payload_fns.payload_76_cmd194(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_REVERSE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -31148,8 +33232,8 @@ function payload_fns.payload_76_cmd194(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_LOCATION -function payload_fns.payload_76_cmd195(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_JUMP +function payload_fns.payload_76_cmd177(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31172,10 +33256,10 @@ function payload_fns.payload_76_cmd195(buffer, tree, msgid, offset, limit, pinfo 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_DO_JUMP_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -31184,16 +33268,16 @@ function payload_fns.payload_76_cmd195(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET -function payload_fns.payload_76_cmd196(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CHANGE_SPEED +function payload_fns.payload_76_cmd178(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31216,28 +33300,28 @@ function payload_fns.payload_76_cmd196(buffer, tree, msgid, offset, limit, pinfo 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_DO_CHANGE_SPEED_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_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_CHANGE_SPEED_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_NONE -function payload_fns.payload_76_cmd197(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_HOME +function payload_fns.payload_76_cmd179(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31260,7 +33344,7 @@ function payload_fns.payload_76_cmd197(buffer, tree, msgid, offset, limit, pinfo 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_DO_SET_HOME_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -31272,16 +33356,16 @@ function payload_fns.payload_76_cmd197(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_SYSID -function payload_fns.payload_76_cmd198(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_PARAMETER +function payload_fns.payload_76_cmd180(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31304,10 +33388,10 @@ function payload_fns.payload_76_cmd198(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_SYSID_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -31324,8 +33408,8 @@ function payload_fns.payload_76_cmd198(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CONTROL_VIDEO -function payload_fns.payload_76_cmd200(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_RELAY +function payload_fns.payload_76_cmd181(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31348,16 +33432,16 @@ function payload_fns.payload_76_cmd200(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -31368,8 +33452,8 @@ function payload_fns.payload_76_cmd200(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI -function payload_fns.payload_76_cmd201(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPEAT_RELAY +function payload_fns.payload_76_cmd182(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31392,13 +33476,13 @@ function payload_fns.payload_76_cmd201(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -31412,52 +33496,8 @@ function payload_fns.payload_76_cmd201(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_DIGICAM_CONFIGURE -function payload_fns.payload_76_cmd202(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param7, tvbrange, value) -end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_DIGICAM_CONTROL -function payload_fns.payload_76_cmd203(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_SERVO +function payload_fns.payload_76_cmd183(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31480,28 +33520,28 @@ function payload_fns.payload_76_cmd203(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONFIGURE -function payload_fns.payload_76_cmd204(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPEAT_SERVO +function payload_fns.payload_76_cmd184(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31524,16 +33564,16 @@ function payload_fns.payload_76_cmd204(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -31544,8 +33584,8 @@ function payload_fns.payload_76_cmd204(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONTROL -function payload_fns.payload_76_cmd205(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FLIGHTTERMINATION +function payload_fns.payload_76_cmd185(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31568,7 +33608,7 @@ function payload_fns.payload_76_cmd205(buffer, tree, msgid, offset, limit, pinfo 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_DO_FLIGHTTERMINATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -31586,10 +33626,10 @@ function payload_fns.payload_76_cmd205(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_CAM_TRIGG_DIST -function payload_fns.payload_76_cmd206(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CHANGE_ALTITUDE +function payload_fns.payload_76_cmd186(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31612,13 +33652,13 @@ function payload_fns.payload_76_cmd206(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -31632,8 +33672,8 @@ function payload_fns.payload_76_cmd206(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FENCE_ENABLE -function payload_fns.payload_76_cmd207(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_RETURN_PATH_START +function payload_fns.payload_76_cmd188(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31656,11 +33696,10 @@ function payload_fns.payload_76_cmd207(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param2, tvbrange, value) - dissect_flags_FENCE_TYPE(subtree, "cmd_MAV_CMD_DO_FENCE_ENABLE_param2", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -31669,16 +33708,16 @@ function payload_fns.payload_76_cmd207(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RETURN_PATH_START_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RETURN_PATH_START_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RETURN_PATH_START_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_PARACHUTE -function payload_fns.payload_76_cmd208(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_LAND_START +function payload_fns.payload_76_cmd189(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31701,7 +33740,7 @@ function payload_fns.payload_76_cmd208(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_PARACHUTE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -31713,16 +33752,16 @@ function payload_fns.payload_76_cmd208(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOTOR_TEST -function payload_fns.payload_76_cmd209(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_RALLY_LAND +function payload_fns.payload_76_cmd190(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31745,28 +33784,28 @@ function payload_fns.payload_76_cmd209(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_INVERTED_FLIGHT -function payload_fns.payload_76_cmd210(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GO_AROUND +function payload_fns.payload_76_cmd191(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31789,7 +33828,7 @@ function payload_fns.payload_76_cmd210(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_INVERTED_FLIGHT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GO_AROUND_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -31809,8 +33848,8 @@ function payload_fns.payload_76_cmd210(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GRIPPER -function payload_fns.payload_76_cmd211(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPOSITION +function payload_fns.payload_76_cmd192(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31833,28 +33872,29 @@ function payload_fns.payload_76_cmd211(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param2, tvbrange, value) + dissect_flags_MAV_DO_REPOSITION_FLAGS(subtree, "cmd_MAV_CMD_DO_REPOSITION_param2", tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_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_REPOSITION_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_AUTOTUNE_ENABLE -function payload_fns.payload_76_cmd212(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_PAUSE_CONTINUE +function payload_fns.payload_76_cmd193(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31877,11 +33917,10 @@ function payload_fns.payload_76_cmd212(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_PAUSE_CONTINUE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2, tvbrange, value) - dissect_flags_AUTOTUNE_AXIS(subtree, "cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -31898,8 +33937,8 @@ function payload_fns.payload_76_cmd212(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SET_YAW_SPEED -function payload_fns.payload_76_cmd213(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_REVERSE +function payload_fns.payload_76_cmd194(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31922,13 +33961,13 @@ function payload_fns.payload_76_cmd213(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_REVERSE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -31942,8 +33981,8 @@ function payload_fns.payload_76_cmd213(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL -function payload_fns.payload_76_cmd214(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_LOCATION +function payload_fns.payload_76_cmd195(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -31966,10 +34005,10 @@ function payload_fns.payload_76_cmd214(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -31978,16 +34017,16 @@ function payload_fns.payload_76_cmd214(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_RESUME_REPEAT_DIST -function payload_fns.payload_76_cmd215(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET +function payload_fns.payload_76_cmd196(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32010,7 +34049,7 @@ function payload_fns.payload_76_cmd215(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RESUME_REPEAT_DIST_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -32022,16 +34061,16 @@ function payload_fns.payload_76_cmd215(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SPRAYER -function payload_fns.payload_76_cmd216(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_NONE +function payload_fns.payload_76_cmd197(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32054,7 +34093,7 @@ function payload_fns.payload_76_cmd216(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SPRAYER_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -32074,8 +34113,8 @@ function payload_fns.payload_76_cmd216(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SEND_SCRIPT_MESSAGE -function payload_fns.payload_76_cmd217(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_SYSID +function payload_fns.payload_76_cmd198(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32098,16 +34137,16 @@ function payload_fns.payload_76_cmd217(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_SYSID_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -32118,8 +34157,8 @@ function payload_fns.payload_76_cmd217(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_AUX_FUNCTION -function payload_fns.payload_76_cmd218(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CONTROL_VIDEO +function payload_fns.payload_76_cmd200(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32142,16 +34181,16 @@ function payload_fns.payload_76_cmd218(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_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_CONTROL_VIDEO_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -32162,8 +34201,8 @@ function payload_fns.payload_76_cmd218(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONTROL_QUAT -function payload_fns.payload_76_cmd220(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI +function payload_fns.payload_76_cmd201(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32186,16 +34225,16 @@ function payload_fns.payload_76_cmd220(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -32206,8 +34245,8 @@ function payload_fns.payload_76_cmd220(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GUIDED_MASTER -function payload_fns.payload_76_cmd221(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_DIGICAM_CONFIGURE +function payload_fns.payload_76_cmd202(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32230,28 +34269,28 @@ function payload_fns.payload_76_cmd221(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_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_DIGICAM_CONFIGURE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GUIDED_LIMITS -function payload_fns.payload_76_cmd222(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_DIGICAM_CONTROL +function payload_fns.payload_76_cmd203(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32274,28 +34313,28 @@ function payload_fns.payload_76_cmd222(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ENGINE_CONTROL -function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONFIGURE +function payload_fns.payload_76_cmd204(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32318,16 +34357,16 @@ function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -32338,8 +34377,8 @@ function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_MISSION_CURRENT -function payload_fns.payload_76_cmd224(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONTROL +function payload_fns.payload_76_cmd205(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32362,7 +34401,7 @@ function payload_fns.payload_76_cmd224(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -32380,10 +34419,10 @@ function payload_fns.payload_76_cmd224(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_LAST -function payload_fns.payload_76_cmd240(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_CAM_TRIGG_DIST +function payload_fns.payload_76_cmd206(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32406,13 +34445,13 @@ function payload_fns.payload_76_cmd240(buffer, tree, msgid, offset, limit, pinfo 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_DO_SET_CAM_TRIGG_DIST_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -32426,8 +34465,8 @@ function payload_fns.payload_76_cmd240(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_CALIBRATION -function payload_fns.payload_76_cmd241(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FENCE_ENABLE +function payload_fns.payload_76_cmd207(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32450,28 +34489,29 @@ function payload_fns.payload_76_cmd241(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param2, tvbrange, value) + dissect_flags_FENCE_TYPE(subtree, "cmd_MAV_CMD_DO_FENCE_ENABLE_param2", tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS -function payload_fns.payload_76_cmd242(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_PARACHUTE +function payload_fns.payload_76_cmd208(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32494,28 +34534,28 @@ function payload_fns.payload_76_cmd242(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_PARACHUTE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_UAVCAN -function payload_fns.payload_76_cmd243(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOTOR_TEST +function payload_fns.payload_76_cmd209(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32538,28 +34578,28 @@ function payload_fns.payload_76_cmd243(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_UAVCAN_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_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_MOTOR_TEST_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_STORAGE -function payload_fns.payload_76_cmd245(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_INVERTED_FLIGHT +function payload_fns.payload_76_cmd210(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32582,13 +34622,13 @@ function payload_fns.payload_76_cmd245(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_INVERTED_FLIGHT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -32602,8 +34642,8 @@ function payload_fns.payload_76_cmd245(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN -function payload_fns.payload_76_cmd246(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GRIPPER +function payload_fns.payload_76_cmd211(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32626,10 +34666,10 @@ function payload_fns.payload_76_cmd246(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -32646,8 +34686,8 @@ function payload_fns.payload_76_cmd246(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_OVERRIDE_GOTO -function payload_fns.payload_76_cmd252(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_AUTOTUNE_ENABLE +function payload_fns.payload_76_cmd212(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32670,28 +34710,29 @@ function payload_fns.payload_76_cmd252(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2, tvbrange, value) + dissect_flags_AUTOTUNE_AXIS(subtree, "cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2", tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_OBLIQUE_SURVEY -function payload_fns.payload_76_cmd260(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SET_YAW_SPEED +function payload_fns.payload_76_cmd213(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32714,28 +34755,28 @@ function payload_fns.payload_76_cmd260(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_MISSION_START -function payload_fns.payload_76_cmd300(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL +function payload_fns.payload_76_cmd214(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32758,10 +34799,10 @@ function payload_fns.payload_76_cmd300(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -32778,8 +34819,8 @@ function payload_fns.payload_76_cmd300(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_COMPONENT_ARM_DISARM -function payload_fns.payload_76_cmd400(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_RESUME_REPEAT_DIST +function payload_fns.payload_76_cmd215(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32802,10 +34843,10 @@ function payload_fns.payload_76_cmd400(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RESUME_REPEAT_DIST_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -32822,8 +34863,8 @@ function payload_fns.payload_76_cmd400(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_RUN_PREARM_CHECKS -function payload_fns.payload_76_cmd401(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SPRAYER +function payload_fns.payload_76_cmd216(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32846,7 +34887,7 @@ function payload_fns.payload_76_cmd401(buffer, tree, msgid, offset, limit, pinfo 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_DO_SPRAYER_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -32866,8 +34907,8 @@ function payload_fns.payload_76_cmd401(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GET_HOME_POSITION -function payload_fns.payload_76_cmd410(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SEND_SCRIPT_MESSAGE +function payload_fns.payload_76_cmd217(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32890,16 +34931,16 @@ function payload_fns.payload_76_cmd410(buffer, tree, msgid, offset, limit, pinfo 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_DO_SEND_SCRIPT_MESSAGE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_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_SEND_SCRIPT_MESSAGE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -32910,8 +34951,8 @@ function payload_fns.payload_76_cmd410(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_START_RX_PAIR -function payload_fns.payload_76_cmd500(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_AUX_FUNCTION +function payload_fns.payload_76_cmd218(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32934,10 +34975,10 @@ function payload_fns.payload_76_cmd500(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -32954,8 +34995,8 @@ function payload_fns.payload_76_cmd500(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GET_MESSAGE_INTERVAL -function payload_fns.payload_76_cmd510(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONTROL_QUAT +function payload_fns.payload_76_cmd220(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -32978,16 +35019,16 @@ function payload_fns.payload_76_cmd510(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GET_MESSAGE_INTERVAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_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_MOUNT_CONTROL_QUAT_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -32998,8 +35039,8 @@ function payload_fns.payload_76_cmd510(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_MESSAGE_INTERVAL -function payload_fns.payload_76_cmd511(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GUIDED_MASTER +function payload_fns.payload_76_cmd221(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33022,10 +35063,10 @@ function payload_fns.payload_76_cmd511(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33040,10 +35081,10 @@ function payload_fns.payload_76_cmd511(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_MESSAGE -function payload_fns.payload_76_cmd512(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GUIDED_LIMITS +function payload_fns.payload_76_cmd222(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33066,28 +35107,28 @@ function payload_fns.payload_76_cmd512(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_PROTOCOL_VERSION -function payload_fns.payload_76_cmd519(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ENGINE_CONTROL +function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33110,16 +35151,16 @@ function payload_fns.payload_76_cmd519(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_PROTOCOL_VERSION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + 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) @@ -33130,8 +35171,8 @@ function payload_fns.payload_76_cmd519(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES -function payload_fns.payload_76_cmd520(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_MISSION_CURRENT +function payload_fns.payload_76_cmd224(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33154,7 +35195,7 @@ function payload_fns.payload_76_cmd520(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -33174,8 +35215,8 @@ function payload_fns.payload_76_cmd520(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_INFORMATION -function payload_fns.payload_76_cmd521(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_LAST +function payload_fns.payload_76_cmd240(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33198,7 +35239,7 @@ function payload_fns.payload_76_cmd521(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_INFORMATION_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -33218,8 +35259,8 @@ function payload_fns.payload_76_cmd521(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_SETTINGS -function payload_fns.payload_76_cmd522(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_CALIBRATION +function payload_fns.payload_76_cmd241(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33242,28 +35283,28 @@ function payload_fns.payload_76_cmd522(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_SETTINGS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_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_PREFLIGHT_CALIBRATION_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_STORAGE_INFORMATION -function payload_fns.payload_76_cmd525(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS +function payload_fns.payload_76_cmd242(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33286,28 +35327,28 @@ function payload_fns.payload_76_cmd525(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_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_PREFLIGHT_SET_SENSOR_OFFSETS_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_STORAGE_FORMAT -function payload_fns.payload_76_cmd526(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_UAVCAN +function payload_fns.payload_76_cmd243(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33330,10 +35371,10 @@ function payload_fns.payload_76_cmd526(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_UAVCAN_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33350,8 +35391,8 @@ function payload_fns.payload_76_cmd526(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS -function payload_fns.payload_76_cmd527(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_STORAGE +function payload_fns.payload_76_cmd245(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33374,13 +35415,13 @@ function payload_fns.payload_76_cmd527(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -33394,8 +35435,8 @@ function payload_fns.payload_76_cmd527(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_FLIGHT_INFORMATION -function payload_fns.payload_76_cmd528(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN +function payload_fns.payload_76_cmd246(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33418,10 +35459,10 @@ function payload_fns.payload_76_cmd528(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_FLIGHT_INFORMATION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33438,8 +35479,8 @@ function payload_fns.payload_76_cmd528(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_RESET_CAMERA_SETTINGS -function payload_fns.payload_76_cmd529(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_OVERRIDE_GOTO +function payload_fns.payload_76_cmd252(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33462,28 +35503,72 @@ function payload_fns.payload_76_cmd529(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_RESET_CAMERA_SETTINGS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_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_OVERRIDE_GOTO_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_OBLIQUE_SURVEY +function payload_fns.payload_76_cmd260(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_MODE -function payload_fns.payload_76_cmd530(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_STANDARD_MODE +function payload_fns.payload_76_cmd262(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33506,10 +35591,10 @@ function payload_fns.payload_76_cmd530(buffer, tree, msgid, offset, limit, pinfo 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_DO_SET_STANDARD_MODE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_MODE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33526,8 +35611,8 @@ function payload_fns.payload_76_cmd530(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_ZOOM -function payload_fns.payload_76_cmd531(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_MISSION_START +function payload_fns.payload_76_cmd300(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33550,10 +35635,10 @@ function payload_fns.payload_76_cmd531(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33570,8 +35655,8 @@ function payload_fns.payload_76_cmd531(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_FOCUS -function payload_fns.payload_76_cmd532(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_COMPONENT_ARM_DISARM +function payload_fns.payload_76_cmd400(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33594,10 +35679,10 @@ function payload_fns.payload_76_cmd532(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33614,8 +35699,8 @@ function payload_fns.payload_76_cmd532(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_STORAGE_USAGE -function payload_fns.payload_76_cmd533(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_RUN_PREARM_CHECKS +function payload_fns.payload_76_cmd401(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33638,10 +35723,10 @@ function payload_fns.payload_76_cmd533(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_STORAGE_USAGE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_STORAGE_USAGE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33658,8 +35743,8 @@ function payload_fns.payload_76_cmd533(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_SOURCE -function payload_fns.payload_76_cmd534(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GET_HOME_POSITION +function payload_fns.payload_76_cmd410(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33682,13 +35767,13 @@ function payload_fns.payload_76_cmd534(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_SOURCE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_SOURCE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_SOURCE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -33702,8 +35787,8 @@ function payload_fns.payload_76_cmd534(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_JUMP_TAG -function payload_fns.payload_76_cmd600(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_START_RX_PAIR +function payload_fns.payload_76_cmd500(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33726,10 +35811,10 @@ function payload_fns.payload_76_cmd600(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_JUMP_TAG_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33746,8 +35831,8 @@ function payload_fns.payload_76_cmd600(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_JUMP_TAG -function payload_fns.payload_76_cmd601(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GET_MESSAGE_INTERVAL +function payload_fns.payload_76_cmd510(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33770,10 +35855,10 @@ function payload_fns.payload_76_cmd601(buffer, tree, msgid, offset, limit, pinfo subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GET_MESSAGE_INTERVAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -33790,53 +35875,8 @@ function payload_fns.payload_76_cmd601(buffer, tree, msgid, offset, limit, pinfo value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW -function payload_fns.payload_76_cmd1000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5, tvbrange, value) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7, tvbrange, value) -end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE -function payload_fns.payload_76_cmd1001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_MESSAGE_INTERVAL +function payload_fns.payload_76_cmd511(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33859,16 +35899,16 @@ function payload_fns.payload_76_cmd1001(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.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -33877,10 +35917,10 @@ function payload_fns.payload_76_cmd1001(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_IMAGE_START_CAPTURE -function payload_fns.payload_76_cmd2000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_MESSAGE +function payload_fns.payload_76_cmd512(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33903,28 +35943,28 @@ 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.cmd_MAV_CMD_IMAGE_START_CAPTURE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_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) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_IMAGE_STOP_CAPTURE -function payload_fns.payload_76_cmd2001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_PROTOCOL_VERSION +function payload_fns.payload_76_cmd519(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33947,7 +35987,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.cmd_MAV_CMD_IMAGE_STOP_CAPTURE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_PROTOCOL_VERSION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -33967,8 +36007,8 @@ function payload_fns.payload_76_cmd2001(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_TRIGGER_CONTROL -function payload_fns.payload_76_cmd2003(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES +function payload_fns.payload_76_cmd520(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -33991,13 +36031,13 @@ function payload_fns.payload_76_cmd2003(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.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -34011,8 +36051,8 @@ function payload_fns.payload_76_cmd2003(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_TRACK_POINT -function payload_fns.payload_76_cmd2004(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_INFORMATION +function payload_fns.payload_76_cmd521(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34035,13 +36075,13 @@ function payload_fns.payload_76_cmd2004(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.cmd_MAV_CMD_CAMERA_TRACK_POINT_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_INFORMATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -34055,8 +36095,8 @@ function payload_fns.payload_76_cmd2004(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_TRACK_RECTANGLE -function payload_fns.payload_76_cmd2005(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_SETTINGS +function payload_fns.payload_76_cmd522(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34079,16 +36119,16 @@ function payload_fns.payload_76_cmd2005(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.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_SETTINGS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -34099,8 +36139,8 @@ function payload_fns.payload_76_cmd2005(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_STOP_TRACKING -function payload_fns.payload_76_cmd2010(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_STORAGE_INFORMATION +function payload_fns.payload_76_cmd525(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34123,10 +36163,10 @@ function payload_fns.payload_76_cmd2010(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_REQUEST_STORAGE_INFORMATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -34143,8 +36183,8 @@ function payload_fns.payload_76_cmd2010(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_START_CAPTURE -function payload_fns.payload_76_cmd2500(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_STORAGE_FORMAT +function payload_fns.payload_76_cmd526(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34167,10 +36207,10 @@ function payload_fns.payload_76_cmd2500(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.cmd_MAV_CMD_VIDEO_START_CAPTURE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -34187,8 +36227,8 @@ function payload_fns.payload_76_cmd2500(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_STOP_CAPTURE -function payload_fns.payload_76_cmd2501(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS +function payload_fns.payload_76_cmd527(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34211,7 +36251,7 @@ function payload_fns.payload_76_cmd2501(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.cmd_MAV_CMD_VIDEO_STOP_CAPTURE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -34231,8 +36271,8 @@ function payload_fns.payload_76_cmd2501(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_START_STREAMING -function payload_fns.payload_76_cmd2502(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_FLIGHT_INFORMATION +function payload_fns.payload_76_cmd528(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34255,7 +36295,7 @@ function payload_fns.payload_76_cmd2502(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.cmd_MAV_CMD_VIDEO_START_STREAMING_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_FLIGHT_INFORMATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -34275,8 +36315,8 @@ function payload_fns.payload_76_cmd2502(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_STOP_STREAMING -function payload_fns.payload_76_cmd2503(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_RESET_CAMERA_SETTINGS +function payload_fns.payload_76_cmd529(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34299,7 +36339,7 @@ function payload_fns.payload_76_cmd2503(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.cmd_MAV_CMD_VIDEO_STOP_STREAMING_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_RESET_CAMERA_SETTINGS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -34319,8 +36359,8 @@ function payload_fns.payload_76_cmd2503(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION -function payload_fns.payload_76_cmd2504(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_MODE +function payload_fns.payload_76_cmd530(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34343,10 +36383,10 @@ function payload_fns.payload_76_cmd2504(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.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_MODE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -34363,8 +36403,8 @@ function payload_fns.payload_76_cmd2504(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_VIDEO_STREAM_STATUS -function payload_fns.payload_76_cmd2505(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_ZOOM +function payload_fns.payload_76_cmd531(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34387,10 +36427,10 @@ function payload_fns.payload_76_cmd2505(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.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_STATUS_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -34407,8 +36447,8 @@ function payload_fns.payload_76_cmd2505(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOGGING_START -function payload_fns.payload_76_cmd2510(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_FOCUS +function payload_fns.payload_76_cmd532(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34431,10 +36471,10 @@ function payload_fns.payload_76_cmd2510(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.cmd_MAV_CMD_LOGGING_START_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -34451,8 +36491,8 @@ function payload_fns.payload_76_cmd2510(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOGGING_STOP -function payload_fns.payload_76_cmd2511(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_STORAGE_USAGE +function payload_fns.payload_76_cmd533(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34475,10 +36515,10 @@ function payload_fns.payload_76_cmd2511(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_SET_STORAGE_USAGE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_STORAGE_USAGE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -34495,8 +36535,8 @@ function payload_fns.payload_76_cmd2511(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_AIRFRAME_CONFIGURATION -function payload_fns.payload_76_cmd2520(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_SOURCE +function payload_fns.payload_76_cmd534(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34519,13 +36559,13 @@ function payload_fns.payload_76_cmd2520(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.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_SOURCE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_SOURCE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_SOURCE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -34539,8 +36579,8 @@ function payload_fns.payload_76_cmd2520(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONTROL_HIGH_LATENCY -function payload_fns.payload_76_cmd2600(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_JUMP_TAG +function payload_fns.payload_76_cmd600(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34563,7 +36603,7 @@ function payload_fns.payload_76_cmd2600(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.cmd_MAV_CMD_CONTROL_HIGH_LATENCY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_JUMP_TAG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -34583,8 +36623,8 @@ function payload_fns.payload_76_cmd2600(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PANORAMA_CREATE -function payload_fns.payload_76_cmd2800(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_JUMP_TAG +function payload_fns.payload_76_cmd601(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34607,16 +36647,16 @@ function payload_fns.payload_76_cmd2800(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.cmd_MAV_CMD_PANORAMA_CREATE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -34627,8 +36667,8 @@ function payload_fns.payload_76_cmd2800(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_VTOL_TRANSITION -function payload_fns.payload_76_cmd3000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_SYS_CMP_ID +function payload_fns.payload_76_cmd610(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34651,13 +36691,13 @@ function payload_fns.payload_76_cmd3000(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.cmd_MAV_CMD_DO_VTOL_TRANSITION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SYS_CMP_ID_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -34671,8 +36711,8 @@ function payload_fns.payload_76_cmd3000(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_ARM_AUTHORIZATION_REQUEST -function payload_fns.payload_76_cmd3001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW +function payload_fns.payload_76_cmd1000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34695,28 +36735,29 @@ function payload_fns.payload_76_cmd3001(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.cmd_MAV_CMD_ARM_AUTHORIZATION_REQUEST_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_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_GIMBAL_MANAGER_PITCHYAW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_GUIDED_SUBMODE_STANDARD -function payload_fns.payload_76_cmd4000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE +function payload_fns.payload_76_cmd1001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34739,16 +36780,16 @@ function payload_fns.payload_76_cmd4000(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_DO_GIMBAL_MANAGER_CONFIGURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_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_GIMBAL_MANAGER_CONFIGURE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -34757,10 +36798,10 @@ function payload_fns.payload_76_cmd4000(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE -function payload_fns.payload_76_cmd4001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_IMAGE_START_CAPTURE +function payload_fns.payload_76_cmd2000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34783,28 +36824,28 @@ function payload_fns.payload_76_cmd4001(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.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_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.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_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_IMAGE_START_CAPTURE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_RETURN_POINT -function payload_fns.payload_76_cmd5000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_IMAGE_STOP_CAPTURE +function payload_fns.payload_76_cmd2001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34827,7 +36868,7 @@ function payload_fns.payload_76_cmd5000(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) @@ -34839,16 +36880,16 @@ function payload_fns.payload_76_cmd5000(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION -function payload_fns.payload_76_cmd5001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_TRIGGER_CONTROL +function payload_fns.payload_76_cmd2003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34871,28 +36912,28 @@ function payload_fns.payload_76_cmd5001(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.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION -function payload_fns.payload_76_cmd5002(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_TRACK_POINT +function payload_fns.payload_76_cmd2004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34915,28 +36956,28 @@ function payload_fns.payload_76_cmd5002(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.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION -function payload_fns.payload_76_cmd5003(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_TRACK_RECTANGLE +function payload_fns.payload_76_cmd2005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -34959,28 +37000,28 @@ function payload_fns.payload_76_cmd5003(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.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_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_CAMERA_TRACK_RECTANGLE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION -function payload_fns.payload_76_cmd5004(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_STOP_TRACKING +function payload_fns.payload_76_cmd2010(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35003,7 +37044,7 @@ function payload_fns.payload_76_cmd5004(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.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35015,16 +37056,16 @@ function payload_fns.payload_76_cmd5004(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_RALLY_POINT -function payload_fns.payload_76_cmd5100(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_START_CAPTURE +function payload_fns.payload_76_cmd2500(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35047,10 +37088,10 @@ function payload_fns.payload_76_cmd5100(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_VIDEO_START_CAPTURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -35059,16 +37100,16 @@ function payload_fns.payload_76_cmd5100(buffer, tree, msgid, offset, limit, pinf subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_UAVCAN_GET_NODE_INFO -function payload_fns.payload_76_cmd5200(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_STOP_CAPTURE +function payload_fns.payload_76_cmd2501(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35091,7 +37132,7 @@ function payload_fns.payload_76_cmd5200(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_VIDEO_STOP_CAPTURE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35111,8 +37152,8 @@ function payload_fns.payload_76_cmd5200(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_SAFETY_SWITCH_STATE -function payload_fns.payload_76_cmd5300(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_START_STREAMING +function payload_fns.payload_76_cmd2502(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35135,7 +37176,7 @@ function payload_fns.payload_76_cmd5300(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.cmd_MAV_CMD_DO_SET_SAFETY_SWITCH_STATE_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_STREAMING_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35155,8 +37196,8 @@ function payload_fns.payload_76_cmd5300(buffer, tree, msgid, offset, limit, pinf value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ADSB_OUT_IDENT -function payload_fns.payload_76_cmd10001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_STOP_STREAMING +function payload_fns.payload_76_cmd2503(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35179,7 +37220,7 @@ function payload_fns.payload_76_cmd10001(buffer, tree, msgid, offset, limit, pin 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_VIDEO_STOP_STREAMING_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35199,8 +37240,8 @@ function payload_fns.payload_76_cmd10001(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOWEHEISER_SET_STATE -function payload_fns.payload_76_cmd10151(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION +function payload_fns.payload_76_cmd2504(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35223,7 +37264,7 @@ function payload_fns.payload_76_cmd10151(buffer, tree, msgid, offset, limit, pin 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_REQUEST_VIDEO_STREAM_INFORMATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35243,8 +37284,8 @@ function payload_fns.payload_76_cmd10151(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_PREPARE_DEPLOY -function payload_fns.payload_76_cmd30001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_VIDEO_STREAM_STATUS +function payload_fns.payload_76_cmd2505(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35267,28 +37308,28 @@ function payload_fns.payload_76_cmd30001(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_STATUS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_CONTROL_DEPLOY -function payload_fns.payload_76_cmd30002(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOGGING_START +function payload_fns.payload_76_cmd2510(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35311,7 +37352,7 @@ function payload_fns.payload_76_cmd30002(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_CONTROL_DEPLOY_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_LOGGING_START_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35331,8 +37372,8 @@ function payload_fns.payload_76_cmd30002(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_1 -function payload_fns.payload_76_cmd31000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOGGING_STOP +function payload_fns.payload_76_cmd2511(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35367,16 +37408,16 @@ function payload_fns.payload_76_cmd31000(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_2 -function payload_fns.payload_76_cmd31001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_AIRFRAME_CONFIGURATION +function payload_fns.payload_76_cmd2520(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35399,10 +37440,10 @@ function payload_fns.payload_76_cmd31001(buffer, tree, msgid, offset, limit, pin 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_AIRFRAME_CONFIGURATION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -35411,16 +37452,16 @@ function payload_fns.payload_76_cmd31001(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_3 -function payload_fns.payload_76_cmd31002(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONTROL_HIGH_LATENCY +function payload_fns.payload_76_cmd2600(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35443,7 +37484,7 @@ function payload_fns.payload_76_cmd31002(buffer, tree, msgid, offset, limit, pin 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_CONTROL_HIGH_LATENCY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35455,16 +37496,16 @@ function payload_fns.payload_76_cmd31002(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_4 -function payload_fns.payload_76_cmd31003(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PANORAMA_CREATE +function payload_fns.payload_76_cmd2800(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35487,7 +37528,51 @@ function payload_fns.payload_76_cmd31003(buffer, tree, msgid, offset, limit, pin 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_PANORAMA_CREATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_VTOL_TRANSITION +function payload_fns.payload_76_cmd3000(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_VTOL_TRANSITION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35499,16 +37584,16 @@ function payload_fns.payload_76_cmd31003(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_5 -function payload_fns.payload_76_cmd31004(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_ARM_AUTHORIZATION_REQUEST +function payload_fns.payload_76_cmd3001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35531,7 +37616,7 @@ function payload_fns.payload_76_cmd31004(buffer, tree, msgid, offset, limit, pin 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_ARM_AUTHORIZATION_REQUEST_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35543,16 +37628,16 @@ function payload_fns.payload_76_cmd31004(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_1 -function payload_fns.payload_76_cmd31005(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_GUIDED_SUBMODE_STANDARD +function payload_fns.payload_76_cmd4000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35587,16 +37672,16 @@ function payload_fns.payload_76_cmd31005(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param6, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_2 -function payload_fns.payload_76_cmd31006(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE +function payload_fns.payload_76_cmd4001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35619,7 +37704,7 @@ function payload_fns.payload_76_cmd31006(buffer, tree, msgid, offset, limit, pin 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_SET_GUIDED_SUBMODE_CIRCLE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35631,16 +37716,16 @@ function payload_fns.payload_76_cmd31006(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_3 -function payload_fns.payload_76_cmd31007(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_RETURN_POINT +function payload_fns.payload_76_cmd5000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35675,16 +37760,16 @@ function payload_fns.payload_76_cmd31007(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_4 -function payload_fns.payload_76_cmd31008(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION +function payload_fns.payload_76_cmd5001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35707,10 +37792,10 @@ function payload_fns.payload_76_cmd31008(buffer, tree, msgid, offset, limit, pin 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_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -35719,16 +37804,16 @@ function payload_fns.payload_76_cmd31008(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_5 -function payload_fns.payload_76_cmd31009(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION +function payload_fns.payload_76_cmd5002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35751,7 +37836,7 @@ function payload_fns.payload_76_cmd31009(buffer, tree, msgid, offset, limit, pin 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_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35763,16 +37848,16 @@ function payload_fns.payload_76_cmd31009(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param7, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_1 -function payload_fns.payload_76_cmd31010(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION +function payload_fns.payload_76_cmd5003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35795,10 +37880,10 @@ function payload_fns.payload_76_cmd31010(buffer, tree, msgid, offset, limit, pin 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_NAV_FENCE_CIRCLE_INCLUSION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -35807,16 +37892,16 @@ function payload_fns.payload_76_cmd31010(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_2 -function payload_fns.payload_76_cmd31011(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION +function payload_fns.payload_76_cmd5004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35839,7 +37924,7 @@ function payload_fns.payload_76_cmd31011(buffer, tree, msgid, offset, limit, pin 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_NAV_FENCE_CIRCLE_EXCLUSION_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35851,16 +37936,16 @@ function payload_fns.payload_76_cmd31011(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_3 -function payload_fns.payload_76_cmd31012(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_RALLY_POINT +function payload_fns.payload_76_cmd5100(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35895,16 +37980,16 @@ function payload_fns.payload_76_cmd31012(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_4 -function payload_fns.payload_76_cmd31013(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_UAVCAN_GET_NODE_INFO +function payload_fns.payload_76_cmd5200(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35947,8 +38032,8 @@ function payload_fns.payload_76_cmd31013(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_5 -function payload_fns.payload_76_cmd31014(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_SAFETY_SWITCH_STATE +function payload_fns.payload_76_cmd5300(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -35971,7 +38056,7 @@ function payload_fns.payload_76_cmd31014(buffer, tree, msgid, offset, limit, pin 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_DO_SET_SAFETY_SWITCH_STATE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -35991,8 +38076,8 @@ function payload_fns.payload_76_cmd31014(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAN_FORWARD -function payload_fns.payload_76_cmd32000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ADSB_OUT_IDENT +function payload_fns.payload_76_cmd10001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36015,7 +38100,7 @@ function payload_fns.payload_76_cmd32000(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_CAN_FORWARD_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36035,8 +38120,8 @@ function payload_fns.payload_76_cmd32000(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_POWER_OFF_INITIATED -function payload_fns.payload_76_cmd42000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOWEHEISER_SET_STATE +function payload_fns.payload_76_cmd10151(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36079,8 +38164,8 @@ function payload_fns.payload_76_cmd42000(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_FLY_CLICK -function payload_fns.payload_76_cmd42001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_PREPARE_DEPLOY +function payload_fns.payload_76_cmd30001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36103,28 +38188,28 @@ function payload_fns.payload_76_cmd42001(buffer, tree, msgid, offset, limit, pin 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_PAYLOAD_PREPARE_DEPLOY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_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_PAYLOAD_PREPARE_DEPLOY_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_FLY_HOLD -function payload_fns.payload_76_cmd42002(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_CONTROL_DEPLOY +function payload_fns.payload_76_cmd30002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36147,7 +38232,7 @@ function payload_fns.payload_76_cmd42002(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_CONTROL_DEPLOY_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36167,8 +38252,8 @@ function payload_fns.payload_76_cmd42002(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_PAUSE_CLICK -function payload_fns.payload_76_cmd42003(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_1 +function payload_fns.payload_76_cmd31000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36191,7 +38276,7 @@ function payload_fns.payload_76_cmd42003(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36203,16 +38288,16 @@ function payload_fns.payload_76_cmd42003(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL -function payload_fns.payload_76_cmd42004(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_2 +function payload_fns.payload_76_cmd31001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36235,28 +38320,28 @@ function payload_fns.payload_76_cmd42004(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL_FIELD -function payload_fns.payload_76_cmd42005(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_3 +function payload_fns.payload_76_cmd31002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36279,28 +38364,28 @@ function payload_fns.payload_76_cmd42005(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL_YAW -function payload_fns.payload_76_cmd42006(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_4 +function payload_fns.payload_76_cmd31003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36323,28 +38408,28 @@ function payload_fns.payload_76_cmd42006(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_EKF_SOURCE_SET -function payload_fns.payload_76_cmd42007(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_5 +function payload_fns.payload_76_cmd31004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36367,7 +38452,7 @@ function payload_fns.payload_76_cmd42007(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36379,16 +38464,16 @@ function payload_fns.payload_76_cmd42007(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_START_MAG_CAL -function payload_fns.payload_76_cmd42424(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_1 +function payload_fns.payload_76_cmd31005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36411,28 +38496,28 @@ function payload_fns.payload_76_cmd42424(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ACCEPT_MAG_CAL -function payload_fns.payload_76_cmd42425(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_2 +function payload_fns.payload_76_cmd31006(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36455,7 +38540,7 @@ function payload_fns.payload_76_cmd42425(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36467,16 +38552,16 @@ function payload_fns.payload_76_cmd42425(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CANCEL_MAG_CAL -function payload_fns.payload_76_cmd42426(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_3 +function payload_fns.payload_76_cmd31007(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36499,7 +38584,7 @@ function payload_fns.payload_76_cmd42426(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36511,16 +38596,16 @@ function payload_fns.payload_76_cmd42426(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_FACTORY_TEST_MODE -function payload_fns.payload_76_cmd42427(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_4 +function payload_fns.payload_76_cmd31008(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36543,7 +38628,7 @@ function payload_fns.payload_76_cmd42427(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36555,16 +38640,16 @@ function payload_fns.payload_76_cmd42427(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SEND_BANNER -function payload_fns.payload_76_cmd42428(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_5 +function payload_fns.payload_76_cmd31009(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36599,16 +38684,16 @@ function payload_fns.payload_76_cmd42428(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_ACCELCAL_VEHICLE_POS -function payload_fns.payload_76_cmd42429(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_1 +function payload_fns.payload_76_cmd31010(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36631,7 +38716,7 @@ function payload_fns.payload_76_cmd42429(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) @@ -36651,8 +38736,8 @@ function payload_fns.payload_76_cmd42429(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_RESET -function payload_fns.payload_76_cmd42501(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_2 +function payload_fns.payload_76_cmd31011(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36695,8 +38780,8 @@ function payload_fns.payload_76_cmd42501(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS -function payload_fns.payload_76_cmd42502(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_3 +function payload_fns.payload_76_cmd31012(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36719,13 +38804,13 @@ function payload_fns.payload_76_cmd42502(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -36739,8 +38824,8 @@ function payload_fns.payload_76_cmd42502(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION -function payload_fns.payload_76_cmd42503(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_4 +function payload_fns.payload_76_cmd31013(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36783,8 +38868,8 @@ function payload_fns.payload_76_cmd42503(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_FULL_RESET -function payload_fns.payload_76_cmd42505(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_5 +function payload_fns.payload_76_cmd31014(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36827,8 +38912,8 @@ function payload_fns.payload_76_cmd42505(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_WINCH -function payload_fns.payload_76_cmd42600(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAN_FORWARD +function payload_fns.payload_76_cmd32000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36851,16 +38936,16 @@ function payload_fns.payload_76_cmd42600(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_CAN_FORWARD_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -36871,8 +38956,8 @@ function payload_fns.payload_76_cmd42600(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_FLASH_BOOTLOADER -function payload_fns.payload_76_cmd42650(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_RESET_MPPT +function payload_fns.payload_76_cmd40001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36907,7 +38992,7 @@ function payload_fns.payload_76_cmd42650(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) @@ -36915,8 +39000,8 @@ function payload_fns.payload_76_cmd42650(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_BATTERY_RESET -function payload_fns.payload_76_cmd42651(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_CONTROL +function payload_fns.payload_76_cmd40002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -36939,10 +39024,10 @@ function payload_fns.payload_76_cmd42651(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) @@ -36959,8 +39044,8 @@ function payload_fns.payload_76_cmd42651(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_DEBUG_TRAP -function payload_fns.payload_76_cmd42700(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_POWER_OFF_INITIATED +function payload_fns.payload_76_cmd42000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37003,8 +39088,8 @@ function payload_fns.payload_76_cmd42700(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SCRIPTING -function payload_fns.payload_76_cmd42701(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_FLY_CLICK +function payload_fns.payload_76_cmd42001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37047,96 +39132,8 @@ function payload_fns.payload_76_cmd42701(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SCRIPT_TIME -function payload_fns.payload_76_cmd42702(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) -end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ATTITUDE_TIME -function payload_fns.payload_76_cmd42703(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) -end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_SPEED -function payload_fns.payload_76_cmd43000(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_FLY_HOLD +function payload_fns.payload_76_cmd42002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37159,13 +39156,13 @@ function payload_fns.payload_76_cmd43000(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -37179,8 +39176,8 @@ function payload_fns.payload_76_cmd43000(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_ALTITUDE -function payload_fns.payload_76_cmd43001(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_PAUSE_CLICK +function payload_fns.payload_76_cmd42003(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37203,57 +39200,13 @@ function payload_fns.payload_76_cmd43001(buffer, tree, msgid, offset, limit, pin 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_SOLO_BTN_PAUSE_CLICK_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, tvbrange, value) -end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_HEADING -function payload_fns.payload_76_cmd43002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -37267,52 +39220,8 @@ function payload_fns.payload_76_cmd43002(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_EXTERNAL_POSITION_ESTIMATE -function payload_fns.payload_76_cmd43003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 33 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 33) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 30, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) - tvbrange = padded(offset + 31, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) - tvbrange = padded(offset + 28, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) - tvbrange = padded(offset + 32, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7, tvbrange, value) -end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_HAGL -function payload_fns.payload_76_cmd43005(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL +function payload_fns.payload_76_cmd42004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37335,16 +39244,16 @@ function payload_fns.payload_76_cmd43005(buffer, tree, msgid, offset, limit, pin subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_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_FIXED_MAG_CAL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -37355,8 +39264,8 @@ function payload_fns.payload_76_cmd43005(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG with command MAV_CMD_ENUM_END -function payload_fns.payload_76_cmd43006(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL_FIELD +function payload_fns.payload_76_cmd42005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37379,13 +39288,13 @@ function payload_fns.payload_76_cmd43006(buffer, tree, msgid, offset, limit, pin 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_FIXED_MAG_CAL_FIELD_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) @@ -37399,8 +39308,8 @@ function payload_fns.payload_76_cmd43006(buffer, tree, msgid, offset, limit, pin value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_LONG -function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL_YAW +function payload_fns.payload_76_cmd42006(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37409,16 +39318,6 @@ function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - local cmd_id = padded(offset + 28, 2):le_uint() - local cmd_name = enumEntryName.MAV_CMD[cmd_id] - if cmd_name ~= nil then - pinfo.cols.info:append(": " .. cmd_name) - end - local cmd_fn = payload_fns["payload_76_cmd" .. tostring(cmd_id)] - if cmd_fn ~= nil then - cmd_fn(buffer, tree, msgid, offset, limit, pinfo) - return - end tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) @@ -37433,16 +39332,16 @@ function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) 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_FIXED_MAG_CAL_YAW_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_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_FIXED_MAG_CAL_YAW_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) @@ -37453,527 +39352,448 @@ function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_float() subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type COMMAND_ACK -function payload_fns.payload_77(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_EKF_SOURCE_SET +function payload_fns.payload_76_cmd42007(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 10 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 10) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - local cmd_id = padded(offset + 0, 2):le_uint() - local cmd_name = enumEntryName.MAV_CMD[cmd_id] - if cmd_name ~= nil then - pinfo.cols.info:append(": " .. cmd_name) - end - tvbrange = padded(offset + 0, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_ACK_command, tvbrange, value) - tvbrange = padded(offset + 2, 1) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_ACK_result, tvbrange, value) - tvbrange = padded(offset + 3, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_ACK_progress, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.COMMAND_ACK_result_param2, tvbrange, value) - tvbrange = padded(offset + 8, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_ACK_target_system, tvbrange, value) - tvbrange = padded(offset + 9, 1) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.COMMAND_ACK_target_component, tvbrange, value) -end --- dissect payload of message type MANUAL_SETPOINT -function payload_fns.payload_81(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 22 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 22) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.MANUAL_SETPOINT_time_boot_ms, tvbrange, value) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.MANUAL_SETPOINT_roll, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.MANUAL_SETPOINT_pitch, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.MANUAL_SETPOINT_yaw, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.MANUAL_SETPOINT_thrust, tvbrange, value) - tvbrange = padded(offset + 20, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.MANUAL_SETPOINT_mode_switch, tvbrange, value) - tvbrange = padded(offset + 21, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.MANUAL_SETPOINT_manual_override_switch, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type SET_ATTITUDE_TARGET -function payload_fns.payload_82(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_START_MAG_CAL +function payload_fns.payload_76_cmd42424(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 39 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 39) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_time_boot_ms, tvbrange, value) - tvbrange = padded(offset + 36, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_target_system, tvbrange, value) - tvbrange = padded(offset + 37, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_target_component, tvbrange, value) - tvbrange = padded(offset + 38, 1) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_type_mask, tvbrange, value) - dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "SET_ATTITUDE_TARGET_type_mask", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_0, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_3, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_roll_rate, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_pitch_rate, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_yaw_rate, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_ATTITUDE_TARGET_thrust, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type ATTITUDE_TARGET -function payload_fns.payload_83(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ACCEPT_MAG_CAL +function payload_fns.payload_76_cmd42425(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 37 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 37) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.ATTITUDE_TARGET_time_boot_ms, tvbrange, value) - tvbrange = padded(offset + 36, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.ATTITUDE_TARGET_type_mask, tvbrange, value) - dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "ATTITUDE_TARGET_type_mask", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_q_0, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_q_1, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_q_2, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_q_3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_body_roll_rate, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_body_pitch_rate, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_body_yaw_rate, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ATTITUDE_TARGET_thrust, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type SET_POSITION_TARGET_LOCAL_NED -function payload_fns.payload_84(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CANCEL_MAG_CAL +function payload_fns.payload_76_cmd42426(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 53 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 53) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_time_boot_ms, tvbrange, value) - tvbrange = padded(offset + 50, 1) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_system, tvbrange, value) - tvbrange = padded(offset + 51, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_component, tvbrange, value) - tvbrange = padded(offset + 52, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_coordinate_frame, tvbrange, value) - tvbrange = padded(offset + 48, 2) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_type_mask, tvbrange, value) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_LOCAL_NED_type_mask", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_x, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_z, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vx, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vy, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vz, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afx, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afy, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afz, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw_rate, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type POSITION_TARGET_LOCAL_NED -function payload_fns.payload_85(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_FACTORY_TEST_MODE +function payload_fns.payload_76_cmd42427(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 51 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 51) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_time_boot_ms, tvbrange, value) - tvbrange = padded(offset + 50, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_coordinate_frame, tvbrange, value) - tvbrange = padded(offset + 48, 2) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_type_mask, tvbrange, value) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_LOCAL_NED_type_mask", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_x, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_z, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vx, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vy, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vz, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afx, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afy, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afz, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw_rate, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type SET_POSITION_TARGET_GLOBAL_INT -function payload_fns.payload_86(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SEND_BANNER +function payload_fns.payload_76_cmd42428(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 53 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 53) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_time_boot_ms, tvbrange, value) - tvbrange = padded(offset + 50, 1) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_system, tvbrange, value) - tvbrange = padded(offset + 51, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_component, tvbrange, value) - tvbrange = padded(offset + 52, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_coordinate_frame, tvbrange, value) - tvbrange = padded(offset + 48, 2) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_type_mask, tvbrange, value) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_GLOBAL_INT_type_mask", tvbrange, value) + 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) tvbrange = padded(offset + 4, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lat_int, tvbrange, value) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lon_int, tvbrange, value) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_alt, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vx, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vy, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vz, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afx, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afy, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afz, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw_rate, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type POSITION_TARGET_GLOBAL_INT -function payload_fns.payload_87(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_ACCELCAL_VEHICLE_POS +function payload_fns.payload_76_cmd42429(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 51 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 51) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_time_boot_ms, tvbrange, value) - tvbrange = padded(offset + 50, 1) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_coordinate_frame, tvbrange, value) - tvbrange = padded(offset + 48, 2) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_type_mask, tvbrange, value) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_GLOBAL_INT_type_mask", tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lat_int, tvbrange, value) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lon_int, tvbrange, value) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_alt, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vx, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vy, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vz, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afx, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afy, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afz, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw_rate, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET -function payload_fns.payload_89(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_RESET +function payload_fns.payload_76_cmd42501(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 28 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 28) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 4) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_time_boot_ms, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_x, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_z, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_roll, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_pitch, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_yaw, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type HIL_STATE -function payload_fns.payload_90(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS +function payload_fns.payload_76_cmd42502(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 56 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 56) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIL_STATE_time_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_STATE_roll, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_STATE_pitch, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_STATE_yaw, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_STATE_rollspeed, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_STATE_pitchspeed, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_STATE_yawspeed, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_lat, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_lon, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_alt, tvbrange, value) - tvbrange = padded(offset + 44, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_vx, tvbrange, value) - tvbrange = padded(offset + 46, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_vy, tvbrange, value) - tvbrange = padded(offset + 48, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_vz, tvbrange, value) - tvbrange = padded(offset + 50, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_xacc, tvbrange, value) - tvbrange = padded(offset + 52, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_yacc, tvbrange, value) - tvbrange = padded(offset + 54, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HIL_STATE_zacc, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type HIL_CONTROLS -function payload_fns.payload_91(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION +function payload_fns.payload_76_cmd42503(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 42 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 42) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIL_CONTROLS_time_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_roll_ailerons, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_pitch_elevator, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_yaw_rudder, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_throttle, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_aux1, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_aux2, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_aux3, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_CONTROLS_aux4, tvbrange, value) - tvbrange = padded(offset + 40, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_CONTROLS_mode, tvbrange, value) - tvbrange = padded(offset + 41, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_CONTROLS_nav_mode, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type HIL_RC_INPUTS_RAW -function payload_fns.payload_92(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_FULL_RESET +function payload_fns.payload_76_cmd42505(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() @@ -37982,708 +39802,2428 @@ function payload_fns.payload_92(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_time_usec, tvbrange, value) - tvbrange = padded(offset + 8, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan1_raw, tvbrange, value) - tvbrange = padded(offset + 10, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan2_raw, tvbrange, value) - tvbrange = padded(offset + 12, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan3_raw, tvbrange, value) - tvbrange = padded(offset + 14, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan4_raw, tvbrange, value) - tvbrange = padded(offset + 16, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan5_raw, tvbrange, value) - tvbrange = padded(offset + 18, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan6_raw, tvbrange, value) - tvbrange = padded(offset + 20, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan7_raw, tvbrange, value) - tvbrange = padded(offset + 22, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan8_raw, tvbrange, value) - tvbrange = padded(offset + 24, 2) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan9_raw, tvbrange, value) - tvbrange = padded(offset + 26, 2) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan10_raw, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan11_raw, tvbrange, value) - tvbrange = padded(offset + 30, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan12_raw, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_rssi, tvbrange, value) -end --- dissect payload of message type HIL_ACTUATOR_CONTROLS -function payload_fns.payload_93(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 81 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 81) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_time_usec, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_0, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_1, tvbrange, value) - tvbrange = padded(offset + 24, 4) + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_2, tvbrange, value) - tvbrange = padded(offset + 28, 4) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_3, tvbrange, value) - tvbrange = padded(offset + 32, 4) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_4, tvbrange, value) - tvbrange = padded(offset + 36, 4) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_5, tvbrange, value) - tvbrange = padded(offset + 40, 4) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_6, tvbrange, value) - tvbrange = padded(offset + 44, 4) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_7, tvbrange, value) - tvbrange = padded(offset + 48, 4) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_8, tvbrange, value) - tvbrange = padded(offset + 52, 4) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_WINCH +function payload_fns.payload_76_cmd42600(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_9, tvbrange, value) - tvbrange = padded(offset + 56, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_10, tvbrange, value) - tvbrange = padded(offset + 60, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_11, tvbrange, value) - tvbrange = padded(offset + 64, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_12, tvbrange, value) - tvbrange = padded(offset + 68, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_13, tvbrange, value) - tvbrange = padded(offset + 72, 4) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_14, tvbrange, value) - tvbrange = padded(offset + 76, 4) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_15, tvbrange, value) - tvbrange = padded(offset + 80, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_mode, tvbrange, value) - dissect_flags_MAV_MODE_FLAG(subtree, "HIL_ACTUATOR_CONTROLS_mode", tvbrange, value) - tvbrange = padded(offset + 8, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_flags, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type OPTICAL_FLOW -function payload_fns.payload_100(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_FLASH_BOOTLOADER +function payload_fns.payload_76_cmd42650(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 34 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 34) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.OPTICAL_FLOW_time_usec, tvbrange, value) - tvbrange = padded(offset + 24, 1) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPTICAL_FLOW_sensor_id, tvbrange, value) - tvbrange = padded(offset + 20, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.OPTICAL_FLOW_flow_x, tvbrange, value) - tvbrange = padded(offset + 22, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.OPTICAL_FLOW_flow_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_x, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_y, tvbrange, value) - tvbrange = padded(offset + 25, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.OPTICAL_FLOW_quality, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_ground_distance, tvbrange, value) - tvbrange = padded(offset + 26, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_flow_rate_x, tvbrange, value) - tvbrange = padded(offset + 30, 4) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_flow_rate_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type GLOBAL_VISION_POSITION_ESTIMATE -function payload_fns.payload_101(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_BATTERY_RESET +function payload_fns.payload_76_cmd42651(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 117 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 117) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_x, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_z, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_roll, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_pitch, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_yaw, tvbrange, value) - tvbrange = padded(offset + 32, 4) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DEBUG_TRAP +function payload_fns.payload_76_cmd42700(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_0, tvbrange, value) - tvbrange = padded(offset + 36, 4) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_1, tvbrange, value) - tvbrange = padded(offset + 40, 4) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_2, tvbrange, value) - tvbrange = padded(offset + 44, 4) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_3, tvbrange, value) - tvbrange = padded(offset + 48, 4) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_4, tvbrange, value) - tvbrange = padded(offset + 52, 4) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_5, tvbrange, value) - tvbrange = padded(offset + 56, 4) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_6, tvbrange, value) - tvbrange = padded(offset + 60, 4) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SCRIPTING +function payload_fns.payload_76_cmd42701(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_7, tvbrange, value) - tvbrange = padded(offset + 64, 4) + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_8, tvbrange, value) - tvbrange = padded(offset + 68, 4) + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_9, tvbrange, value) - tvbrange = padded(offset + 72, 4) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_10, tvbrange, value) - tvbrange = padded(offset + 76, 4) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_11, tvbrange, value) - tvbrange = padded(offset + 80, 4) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_12, tvbrange, value) - tvbrange = padded(offset + 84, 4) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_13, tvbrange, value) - tvbrange = padded(offset + 88, 4) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SCRIPT_TIME +function payload_fns.payload_76_cmd42702(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_14, tvbrange, value) - tvbrange = padded(offset + 92, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_15, tvbrange, value) - tvbrange = padded(offset + 96, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_16, tvbrange, value) - tvbrange = padded(offset + 100, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_17, tvbrange, value) - tvbrange = padded(offset + 104, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_18, tvbrange, value) - tvbrange = padded(offset + 108, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_19, tvbrange, value) - tvbrange = padded(offset + 112, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_20, tvbrange, value) - tvbrange = padded(offset + 116, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_reset_counter, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type VISION_POSITION_ESTIMATE -function payload_fns.payload_102(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ATTITUDE_TIME +function payload_fns.payload_76_cmd42703(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 117 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 117) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_y, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_z, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_roll, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_pitch, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_yaw, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_0, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_1, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_2, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_3, tvbrange, value) - tvbrange = padded(offset + 48, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_4, tvbrange, value) - tvbrange = padded(offset + 52, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_5, tvbrange, value) - tvbrange = padded(offset + 56, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_6, tvbrange, value) - tvbrange = padded(offset + 60, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_7, tvbrange, value) - tvbrange = padded(offset + 64, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_8, tvbrange, value) - tvbrange = padded(offset + 68, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_9, tvbrange, value) - tvbrange = padded(offset + 72, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_10, tvbrange, value) - tvbrange = padded(offset + 76, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_11, tvbrange, value) - tvbrange = padded(offset + 80, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_12, tvbrange, value) - tvbrange = padded(offset + 84, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_13, tvbrange, value) - tvbrange = padded(offset + 88, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_14, tvbrange, value) - tvbrange = padded(offset + 92, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_15, tvbrange, value) - tvbrange = padded(offset + 96, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_16, tvbrange, value) - tvbrange = padded(offset + 100, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_17, tvbrange, value) - tvbrange = padded(offset + 104, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_18, tvbrange, value) - tvbrange = padded(offset + 108, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_19, tvbrange, value) - tvbrange = padded(offset + 112, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_20, tvbrange, value) - tvbrange = padded(offset + 116, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_reset_counter, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type VISION_SPEED_ESTIMATE -function payload_fns.payload_103(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_SPEED +function payload_fns.payload_76_cmd43000(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 57 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 57) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_z, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_0, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_1, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_2, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_3, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_4, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_5, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_6, tvbrange, value) - tvbrange = padded(offset + 48, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_7, tvbrange, value) - tvbrange = padded(offset + 52, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_8, tvbrange, value) - tvbrange = padded(offset + 56, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_reset_counter, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type VICON_POSITION_ESTIMATE -function payload_fns.payload_104(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_ALTITUDE +function payload_fns.payload_76_cmd43001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 116 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 116) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_z, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_roll, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_pitch, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_yaw, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_0, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_1, tvbrange, value) - tvbrange = padded(offset + 40, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_2, tvbrange, value) - tvbrange = padded(offset + 44, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_3, tvbrange, value) - tvbrange = padded(offset + 48, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_4, tvbrange, value) - tvbrange = padded(offset + 52, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_5, tvbrange, value) - tvbrange = padded(offset + 56, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_6, tvbrange, value) - tvbrange = padded(offset + 60, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_7, tvbrange, value) - tvbrange = padded(offset + 64, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_8, tvbrange, value) - tvbrange = padded(offset + 68, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_9, tvbrange, value) - tvbrange = padded(offset + 72, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_10, tvbrange, value) - tvbrange = padded(offset + 76, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_11, tvbrange, value) - tvbrange = padded(offset + 80, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_12, tvbrange, value) - tvbrange = padded(offset + 84, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_13, tvbrange, value) - tvbrange = padded(offset + 88, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_14, tvbrange, value) - tvbrange = padded(offset + 92, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_15, tvbrange, value) - tvbrange = padded(offset + 96, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_16, tvbrange, value) - tvbrange = padded(offset + 100, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_17, tvbrange, value) - tvbrange = padded(offset + 104, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_18, tvbrange, value) - tvbrange = padded(offset + 108, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_19, tvbrange, value) - tvbrange = padded(offset + 112, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_20, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, tvbrange, value) end --- dissect payload of message type HIGHRES_IMU -function payload_fns.payload_105(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_HEADING +function payload_fns.payload_76_cmd43002(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 63 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 63) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIGHRES_IMU_time_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_xacc, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_yacc, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_zacc, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_xgyro, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_ygyro, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_zgyro, tvbrange, value) - tvbrange = padded(offset + 32, 4) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_EXTERNAL_POSITION_ESTIMATE +function payload_fns.payload_76_cmd43003(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_xmag, tvbrange, value) - tvbrange = padded(offset + 36, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_ymag, tvbrange, value) - tvbrange = padded(offset + 40, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_zmag, tvbrange, value) - tvbrange = padded(offset + 44, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_abs_pressure, tvbrange, value) - tvbrange = padded(offset + 48, 4) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_diff_pressure, tvbrange, value) - tvbrange = padded(offset + 52, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_pressure_alt, tvbrange, value) - tvbrange = padded(offset + 56, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIGHRES_IMU_temperature, tvbrange, value) - tvbrange = padded(offset + 60, 2) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIGHRES_IMU_fields_updated, tvbrange, value) - tvbrange = padded(offset + 62, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIGHRES_IMU_id, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7, tvbrange, value) end --- dissect payload of message type OPTICAL_FLOW_RAD -function payload_fns.payload_106(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_EXTERNAL_WIND_ESTIMATE +function payload_fns.payload_76_cmd43004(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 44 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 44) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_time_usec, tvbrange, value) - tvbrange = padded(offset + 42, 1) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_sensor_id, tvbrange, value) - tvbrange = padded(offset + 8, 4) + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integration_time_us, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_x, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_WIND_ESTIMATE_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_y, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_xgyro, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_ygyro, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_zgyro, tvbrange, value) - tvbrange = padded(offset + 40, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_temperature, tvbrange, value) - tvbrange = padded(offset + 43, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_quality, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_time_delta_distance_us, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.OPTICAL_FLOW_RAD_distance, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end --- dissect payload of message type HIL_SENSOR -function payload_fns.payload_107(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_HAGL +function payload_fns.payload_76_cmd43005(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 65 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 65) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 0, 8) - value = tvbrange:le_uint64() - subtree = tree:add_le(f.HIL_SENSOR_time_usec, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param2, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_xacc, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_SET_HAGL_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_yacc, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_zacc, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_xgyro, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_ygyro, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_zgyro, tvbrange, value) - tvbrange = padded(offset + 32, 4) + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW +function payload_fns.payload_76_cmd60002(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_xmag, tvbrange, value) - tvbrange = padded(offset + 36, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_ymag, tvbrange, value) - tvbrange = padded(offset + 40, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_zmag, tvbrange, value) - tvbrange = padded(offset + 44, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_abs_pressure, tvbrange, value) - tvbrange = padded(offset + 48, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_diff_pressure, tvbrange, value) - tvbrange = padded(offset + 52, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param5", tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_pressure_alt, tvbrange, value) - tvbrange = padded(offset + 56, 4) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param6", tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.HIL_SENSOR_temperature, tvbrange, value) - tvbrange = padded(offset + 60, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_SENSOR_fields_updated, tvbrange, value) - tvbrange = padded(offset + 64, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HIL_SENSOR_id, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW_param7, tvbrange, value) end --- dissect payload of message type SIM_STATE -function payload_fns.payload_108(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP +function payload_fns.payload_76_cmd60010(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 92 > limit) then + if (offset + 33 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 92) + padded:set_size(offset + 33) padded = padded:tvb("Untruncated payload") else padded = buffer end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) tvbrange = padded(offset + 0, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_q1, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param1, tvbrange, value) tvbrange = padded(offset + 4, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_q2, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS(subtree, "cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param2", tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_q3, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) tvbrange = padded(offset + 12, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_q4, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) tvbrange = padded(offset + 16, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_roll, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) tvbrange = padded(offset + 20, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_pitch, tvbrange, value) + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) tvbrange = padded(offset + 24, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_yaw, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_xacc, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_yacc, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.SIM_STATE_zacc, tvbrange, value) + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_STORM32_DO_GIMBAL_ACTION +function payload_fns.payload_76_cmd60011(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_STORM32_DO_GIMBAL_ACTION_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_QSHOT_DO_CONFIGURE +function payload_fns.payload_76_cmd60020(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_QSHOT_DO_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_SET_ARM +function payload_fns.payload_76_cmd60050(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PRS_SET_ARM_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_GET_ARM +function payload_fns.payload_76_cmd60051(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_GET_BATTERY +function payload_fns.payload_76_cmd60052(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_GET_ERR +function payload_fns.payload_76_cmd60053(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_SET_ARM_ALTI +function payload_fns.payload_76_cmd60070(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PRS_SET_ARM_ALTI_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_GET_ARM_ALTI +function payload_fns.payload_76_cmd60071(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_PRS_SHUTDOWN +function payload_fns.payload_76_cmd60072(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_ENUM_END +function payload_fns.payload_76_cmd60073(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG +function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + local cmd_id = padded(offset + 28, 2):le_uint() + local cmd_name = enumEntryName.MAV_CMD[cmd_id] + if cmd_name ~= nil then + pinfo.cols.info:append(": " .. cmd_name) + end + local cmd_fn = payload_fns["payload_76_cmd" .. tostring(cmd_id)] + if cmd_fn ~= nil then + cmd_fn(buffer, tree, msgid, offset, limit, pinfo) + return + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + 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) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_ACK +function payload_fns.payload_77(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 10 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 10) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + local cmd_id = padded(offset + 0, 2):le_uint() + local cmd_name = enumEntryName.MAV_CMD[cmd_id] + if cmd_name ~= nil then + pinfo.cols.info:append(": " .. cmd_name) + end + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_command, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_result, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_progress, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_ACK_result_param2, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_target_component, tvbrange, value) +end +-- dissect payload of message type MANUAL_SETPOINT +function payload_fns.payload_81(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 22 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 22) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_SETPOINT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_roll, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_pitch, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_yaw, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_thrust, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_SETPOINT_mode_switch, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_SETPOINT_manual_override_switch, tvbrange, value) +end +-- dissect payload of message type SET_ATTITUDE_TARGET +function payload_fns.payload_82(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 39 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 39) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_target_system, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_target_component, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_type_mask, tvbrange, value) + dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "SET_ATTITUDE_TARGET_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_roll_rate, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_yaw_rate, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_thrust, tvbrange, value) +end +-- dissect payload of message type ATTITUDE_TARGET +function payload_fns.payload_83(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 37 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 37) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ATTITUDE_TARGET_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ATTITUDE_TARGET_type_mask, tvbrange, value) + dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "ATTITUDE_TARGET_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_body_roll_rate, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_body_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_body_yaw_rate, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_thrust, tvbrange, value) +end +-- dissect payload of message type SET_POSITION_TARGET_LOCAL_NED +function payload_fns.payload_84(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 53 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 53) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_system, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_component, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_LOCAL_NED_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw_rate, tvbrange, value) +end +-- dissect payload of message type POSITION_TARGET_LOCAL_NED +function payload_fns.payload_85(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 51 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 51) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_LOCAL_NED_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw_rate, tvbrange, value) +end +-- dissect payload of message type SET_POSITION_TARGET_GLOBAL_INT +function payload_fns.payload_86(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 53 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 53) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_GLOBAL_INT_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lat_int, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lon_int, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw_rate, tvbrange, value) +end +-- dissect payload of message type POSITION_TARGET_GLOBAL_INT +function payload_fns.payload_87(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 51 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 51) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_GLOBAL_INT_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lat_int, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lon_int, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw_rate, tvbrange, value) +end +-- dissect payload of message type LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET +function payload_fns.payload_89(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 28 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 28) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_roll, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_pitch, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_yaw, tvbrange, value) +end +-- dissect payload of message type HIL_STATE +function payload_fns.payload_90(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 56 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 56) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_STATE_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_roll, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_pitch, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_yaw, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_rollspeed, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_yawspeed, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_lat, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_lon, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_alt, tvbrange, value) + tvbrange = padded(offset + 44, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_vx, tvbrange, value) + tvbrange = padded(offset + 46, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_vy, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_vz, tvbrange, value) + tvbrange = padded(offset + 50, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_xacc, tvbrange, value) + tvbrange = padded(offset + 52, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_yacc, tvbrange, value) + tvbrange = padded(offset + 54, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_zacc, tvbrange, value) +end +-- dissect payload of message type HIL_CONTROLS +function payload_fns.payload_91(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 42 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 42) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_CONTROLS_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_roll_ailerons, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_pitch_elevator, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_yaw_rudder, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_throttle, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux4, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_CONTROLS_mode, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_CONTROLS_nav_mode, tvbrange, value) +end +-- dissect payload of message type HIL_RC_INPUTS_RAW +function payload_fns.payload_92(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan1_raw, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan2_raw, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan3_raw, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan4_raw, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan5_raw, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan6_raw, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan7_raw, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan8_raw, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan9_raw, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan10_raw, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan11_raw, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan12_raw, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_rssi, tvbrange, value) +end +-- dissect payload of message type HIL_ACTUATOR_CONTROLS +function payload_fns.payload_93(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 81 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 81) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_time_usec, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_0, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_1, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_2, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_3, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_4, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_5, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_6, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_7, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_8, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_9, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_10, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_11, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_12, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_13, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_14, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_15, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_mode, tvbrange, value) + dissect_flags_MAV_MODE_FLAG(subtree, "HIL_ACTUATOR_CONTROLS_mode", tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_flags, tvbrange, value) +end +-- dissect payload of message type OPTICAL_FLOW +function payload_fns.payload_100(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 34 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 34) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.OPTICAL_FLOW_time_usec, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_sensor_id, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_x, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_y, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_quality, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_ground_distance, tvbrange, value) + tvbrange = padded(offset + 26, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_rate_x, tvbrange, value) + tvbrange = padded(offset + 30, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_rate_y, tvbrange, value) +end +-- dissect payload of message type GLOBAL_VISION_POSITION_ESTIMATE +function payload_fns.payload_101(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 117 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 117) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_roll, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_pitch, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_yaw, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_9, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_10, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_11, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_12, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_13, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_14, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_15, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_17, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_18, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_19, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_20, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_reset_counter, tvbrange, value) +end +-- dissect payload of message type VISION_POSITION_ESTIMATE +function payload_fns.payload_102(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 117 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 117) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_roll, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_pitch, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_yaw, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_9, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_10, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_11, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_12, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_13, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_14, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_15, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_17, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_18, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_19, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_20, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_reset_counter, tvbrange, value) +end +-- dissect payload of message type VISION_SPEED_ESTIMATE +function payload_fns.payload_103(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 57 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 57) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_reset_counter, tvbrange, value) +end +-- dissect payload of message type VICON_POSITION_ESTIMATE +function payload_fns.payload_104(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 116 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 116) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_roll, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_pitch, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_yaw, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_9, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_10, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_11, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_12, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_13, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_14, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_15, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_17, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_18, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_19, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_20, tvbrange, value) +end +-- dissect payload of message type HIGHRES_IMU +function payload_fns.payload_105(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 63 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 63) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIGHRES_IMU_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_xacc, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_yacc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_zacc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_zgyro, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_xmag, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_ymag, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_zmag, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_abs_pressure, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_diff_pressure, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_pressure_alt, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_temperature, tvbrange, value) + tvbrange = padded(offset + 60, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGHRES_IMU_fields_updated, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGHRES_IMU_id, tvbrange, value) +end +-- dissect payload of message type OPTICAL_FLOW_RAD +function payload_fns.payload_106(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 44 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 44) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_time_usec, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_sensor_id, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integration_time_us, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_zgyro, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_temperature, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_quality, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_time_delta_distance_us, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_distance, tvbrange, value) +end +-- dissect payload of message type HIL_SENSOR +function payload_fns.payload_107(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 65 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 65) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_SENSOR_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_xacc, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_yacc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_zacc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_zgyro, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_xmag, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_ymag, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_zmag, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_abs_pressure, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_diff_pressure, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_pressure_alt, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_temperature, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_SENSOR_fields_updated, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_SENSOR_id, tvbrange, value) +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 + 92 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 92) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_roll, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_pitch, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_yaw, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_xacc, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_yacc, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_zacc, tvbrange, value) tvbrange = padded(offset + 40, 4) value = tvbrange:le_float() subtree = tree:add_le(f.SIM_STATE_xgyro, tvbrange, value) @@ -49371,6 +52911,295 @@ function payload_fns.payload_331(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_int() subtree = tree:add_le(f.ODOMETRY_quality, tvbrange, value) end +-- dissect payload of message type TRAJECTORY_REPRESENTATION_WAYPOINTS +function payload_fns.payload_332(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 239 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 239) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_time_usec, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_valid_points, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_x_4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_2, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_3, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_y_4, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_0, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_1, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_2, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_3, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_z_4, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_0, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_1, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_2, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_3, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_x_4, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_0, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_1, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_2, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_3, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_y_4, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_0, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_1, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_2, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_3, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_z_4, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_0, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_1, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_2, tvbrange, value) + tvbrange = padded(offset + 140, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_3, tvbrange, value) + tvbrange = padded(offset + 144, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_x_4, tvbrange, value) + tvbrange = padded(offset + 148, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_0, tvbrange, value) + tvbrange = padded(offset + 152, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_1, tvbrange, value) + tvbrange = padded(offset + 156, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_2, tvbrange, value) + tvbrange = padded(offset + 160, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_3, tvbrange, value) + tvbrange = padded(offset + 164, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_y_4, tvbrange, value) + tvbrange = padded(offset + 168, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_0, tvbrange, value) + tvbrange = padded(offset + 172, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_1, tvbrange, value) + tvbrange = padded(offset + 176, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_2, tvbrange, value) + tvbrange = padded(offset + 180, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_3, tvbrange, value) + tvbrange = padded(offset + 184, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_acc_z_4, tvbrange, value) + tvbrange = padded(offset + 188, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_0, tvbrange, value) + tvbrange = padded(offset + 192, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_1, tvbrange, value) + tvbrange = padded(offset + 196, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_2, tvbrange, value) + tvbrange = padded(offset + 200, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_3, tvbrange, value) + tvbrange = padded(offset + 204, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_pos_yaw_4, tvbrange, value) + tvbrange = padded(offset + 208, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_0, tvbrange, value) + tvbrange = padded(offset + 212, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_1, tvbrange, value) + tvbrange = padded(offset + 216, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_2, tvbrange, value) + tvbrange = padded(offset + 220, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_3, tvbrange, value) + tvbrange = padded(offset + 224, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_vel_yaw_4, tvbrange, value) + tvbrange = padded(offset + 228, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_0, tvbrange, value) + tvbrange = padded(offset + 230, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_1, tvbrange, value) + tvbrange = padded(offset + 232, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_2, tvbrange, value) + tvbrange = padded(offset + 234, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_3, tvbrange, value) + tvbrange = padded(offset + 236, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_WAYPOINTS_command_4, tvbrange, value) +end +-- dissect payload of message type TRAJECTORY_REPRESENTATION_BEZIER +function payload_fns.payload_333(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 109 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 109) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_time_usec, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_valid_points, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_x_4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_2, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_3, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_y_4, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_0, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_1, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_2, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_3, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_z_4, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_delta_0, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_delta_1, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_delta_2, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_delta_3, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_delta_4, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_0, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_1, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_2, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_3, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TRAJECTORY_REPRESENTATION_BEZIER_pos_yaw_4, tvbrange, value) +end -- dissect payload of message type ISBD_LINK_STATUS function payload_fns.payload_335(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -51789,572 +55618,1530 @@ function payload_fns.payload_12915(buffer, tree, msgid, offset, limit, pinfo) subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_51, tvbrange, value) tvbrange = padded(offset + 76, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_52, tvbrange, value) - tvbrange = padded(offset + 77, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_52, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_53, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_54, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_55, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_56, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_57, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_58, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_59, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_60, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_61, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_62, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_63, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_64, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_65, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_66, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_67, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_68, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_69, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_70, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_71, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_72, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_73, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_74, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_75, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_76, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_77, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_78, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_79, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_80, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_81, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_82, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_83, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_84, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_85, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_86, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_87, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_88, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_89, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_90, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_91, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_92, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_93, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_94, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_95, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_96, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_97, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_98, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_99, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_100, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_101, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_102, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_103, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_104, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_105, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_106, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_107, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_108, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_109, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_110, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_111, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_112, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_113, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_114, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_115, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_116, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_117, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_118, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_119, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_120, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_121, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_122, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_123, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_124, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_125, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_126, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_127, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_128, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_129, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_130, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_131, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_132, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_133, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_134, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_135, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_136, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_137, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_138, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_139, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_140, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_141, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_142, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_143, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_144, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_145, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_146, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_147, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_148, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_149, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_150, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_151, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_152, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_153, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_154, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_155, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_156, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_157, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_158, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_159, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_160, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_161, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_162, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_163, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_164, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_165, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_166, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_167, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_168, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_169, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_170, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_171, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_172, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_173, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_174, tvbrange, value) + tvbrange = padded(offset + 199, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_53, tvbrange, value) - tvbrange = padded(offset + 78, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_175, tvbrange, value) + tvbrange = padded(offset + 200, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_54, tvbrange, value) - tvbrange = padded(offset + 79, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_176, tvbrange, value) + tvbrange = padded(offset + 201, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_55, tvbrange, value) - tvbrange = padded(offset + 80, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_177, tvbrange, value) + tvbrange = padded(offset + 202, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_56, tvbrange, value) - tvbrange = padded(offset + 81, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_178, tvbrange, value) + tvbrange = padded(offset + 203, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_57, tvbrange, value) - tvbrange = padded(offset + 82, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_179, tvbrange, value) + tvbrange = padded(offset + 204, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_58, tvbrange, value) - tvbrange = padded(offset + 83, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_180, tvbrange, value) + tvbrange = padded(offset + 205, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_59, tvbrange, value) - tvbrange = padded(offset + 84, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_181, tvbrange, value) + tvbrange = padded(offset + 206, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_60, tvbrange, value) - tvbrange = padded(offset + 85, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_182, tvbrange, value) + tvbrange = padded(offset + 207, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_61, tvbrange, value) - tvbrange = padded(offset + 86, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_183, tvbrange, value) + tvbrange = padded(offset + 208, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_62, tvbrange, value) - tvbrange = padded(offset + 87, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_184, tvbrange, value) + tvbrange = padded(offset + 209, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_63, tvbrange, value) - tvbrange = padded(offset + 88, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_185, tvbrange, value) + tvbrange = padded(offset + 210, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_64, tvbrange, value) - tvbrange = padded(offset + 89, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_186, tvbrange, value) + tvbrange = padded(offset + 211, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_65, tvbrange, value) - tvbrange = padded(offset + 90, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_187, tvbrange, value) + tvbrange = padded(offset + 212, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_66, tvbrange, value) - tvbrange = padded(offset + 91, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_188, tvbrange, value) + tvbrange = padded(offset + 213, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_67, tvbrange, value) - tvbrange = padded(offset + 92, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_189, tvbrange, value) + tvbrange = padded(offset + 214, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_68, tvbrange, value) - tvbrange = padded(offset + 93, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_190, tvbrange, value) + tvbrange = padded(offset + 215, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_69, tvbrange, value) - tvbrange = padded(offset + 94, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_191, tvbrange, value) + tvbrange = padded(offset + 216, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_70, tvbrange, value) - tvbrange = padded(offset + 95, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_192, tvbrange, value) + tvbrange = padded(offset + 217, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_71, tvbrange, value) - tvbrange = padded(offset + 96, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_193, tvbrange, value) + tvbrange = padded(offset + 218, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_72, tvbrange, value) - tvbrange = padded(offset + 97, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_194, tvbrange, value) + tvbrange = padded(offset + 219, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_73, tvbrange, value) - tvbrange = padded(offset + 98, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_195, tvbrange, value) + tvbrange = padded(offset + 220, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_74, tvbrange, value) - tvbrange = padded(offset + 99, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_196, tvbrange, value) + tvbrange = padded(offset + 221, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_75, tvbrange, value) - tvbrange = padded(offset + 100, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_197, tvbrange, value) + tvbrange = padded(offset + 222, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_76, tvbrange, value) - tvbrange = padded(offset + 101, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_198, tvbrange, value) + tvbrange = padded(offset + 223, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_77, tvbrange, value) - tvbrange = padded(offset + 102, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_199, tvbrange, value) + tvbrange = padded(offset + 224, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_78, tvbrange, value) - tvbrange = padded(offset + 103, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_200, tvbrange, value) + tvbrange = padded(offset + 225, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_79, tvbrange, value) - tvbrange = padded(offset + 104, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_201, tvbrange, value) + tvbrange = padded(offset + 226, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_80, tvbrange, value) - tvbrange = padded(offset + 105, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_202, tvbrange, value) + tvbrange = padded(offset + 227, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_81, tvbrange, value) - tvbrange = padded(offset + 106, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_203, tvbrange, value) + tvbrange = padded(offset + 228, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_82, tvbrange, value) - tvbrange = padded(offset + 107, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_204, tvbrange, value) + tvbrange = padded(offset + 229, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_83, tvbrange, value) - tvbrange = padded(offset + 108, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_205, tvbrange, value) + tvbrange = padded(offset + 230, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_84, tvbrange, value) - tvbrange = padded(offset + 109, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_206, tvbrange, value) + tvbrange = padded(offset + 231, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_85, tvbrange, value) - tvbrange = padded(offset + 110, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_207, tvbrange, value) + tvbrange = padded(offset + 232, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_86, tvbrange, value) - tvbrange = padded(offset + 111, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_208, tvbrange, value) + tvbrange = padded(offset + 233, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_87, tvbrange, value) - tvbrange = padded(offset + 112, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_209, tvbrange, value) + tvbrange = padded(offset + 234, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_88, tvbrange, value) - tvbrange = padded(offset + 113, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_210, tvbrange, value) + tvbrange = padded(offset + 235, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_89, tvbrange, value) - tvbrange = padded(offset + 114, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_211, tvbrange, value) + tvbrange = padded(offset + 236, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_90, tvbrange, value) - tvbrange = padded(offset + 115, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_212, tvbrange, value) + tvbrange = padded(offset + 237, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_91, tvbrange, value) - tvbrange = padded(offset + 116, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_213, tvbrange, value) + tvbrange = padded(offset + 238, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_92, tvbrange, value) - tvbrange = padded(offset + 117, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_214, tvbrange, value) + tvbrange = padded(offset + 239, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_93, tvbrange, value) - tvbrange = padded(offset + 118, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_215, tvbrange, value) + tvbrange = padded(offset + 240, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_94, tvbrange, value) - tvbrange = padded(offset + 119, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_216, tvbrange, value) + tvbrange = padded(offset + 241, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_95, tvbrange, value) - tvbrange = padded(offset + 120, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_217, tvbrange, value) + tvbrange = padded(offset + 242, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_96, tvbrange, value) - tvbrange = padded(offset + 121, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_218, tvbrange, value) + tvbrange = padded(offset + 243, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_97, tvbrange, value) - tvbrange = padded(offset + 122, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_219, tvbrange, value) + tvbrange = padded(offset + 244, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_98, tvbrange, value) - tvbrange = padded(offset + 123, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_220, tvbrange, value) + tvbrange = padded(offset + 245, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_99, tvbrange, value) - tvbrange = padded(offset + 124, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_221, tvbrange, value) + tvbrange = padded(offset + 246, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_100, tvbrange, value) - tvbrange = padded(offset + 125, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_222, tvbrange, value) + tvbrange = padded(offset + 247, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_101, tvbrange, value) - tvbrange = padded(offset + 126, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_223, tvbrange, value) + tvbrange = padded(offset + 248, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_102, tvbrange, value) - tvbrange = padded(offset + 127, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_224, tvbrange, value) +end +-- dissect payload of message type OPEN_DRONE_ID_SYSTEM_UPDATE +function payload_fns.payload_12919(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 18 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 18) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 16, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_103, tvbrange, value) - tvbrange = padded(offset + 128, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_system, tvbrange, value) + tvbrange = padded(offset + 17, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_104, tvbrange, value) - tvbrange = padded(offset + 129, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_altitude_geo, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_105, tvbrange, value) - tvbrange = padded(offset + 130, 1) + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_timestamp, tvbrange, value) +end +-- dissect payload of message type HYGROMETER_SENSOR +function payload_fns.payload_12920(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 5 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 5) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 4, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_106, tvbrange, value) - tvbrange = padded(offset + 131, 1) + subtree = tree:add_le(f.HYGROMETER_SENSOR_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HYGROMETER_SENSOR_temperature, tvbrange, value) + tvbrange = padded(offset + 2, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_107, tvbrange, value) - tvbrange = padded(offset + 132, 1) + subtree = tree:add_le(f.HYGROMETER_SENSOR_humidity, tvbrange, value) +end +-- dissect payload of message type MISSION_CHECKSUM +function payload_fns.payload_53(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 5 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 5) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 4, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_108, tvbrange, value) - tvbrange = padded(offset + 133, 1) + subtree = tree:add_le(f.MISSION_CHECKSUM_mission_type, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_109, tvbrange, value) - tvbrange = padded(offset + 134, 1) + subtree = tree:add_le(f.MISSION_CHECKSUM_checksum, tvbrange, value) +end +-- dissect payload of message type AIRSPEED +function payload_fns.payload_295(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 12 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 12) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 10, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_110, tvbrange, value) - tvbrange = padded(offset + 135, 1) + subtree = tree:add_le(f.AIRSPEED_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_airspeed, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.AIRSPEED_temperature, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_raw_press, tvbrange, value) + tvbrange = padded(offset + 11, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_111, tvbrange, value) - tvbrange = padded(offset + 136, 1) + subtree = tree:add_le(f.AIRSPEED_flags, tvbrange, value) + dissect_flags_AIRSPEED_SENSOR_FLAGS(subtree, "AIRSPEED_flags", tvbrange, value) +end +-- dissect payload of message type RADIO_RC_CHANNELS +function payload_fns.payload_420(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 73 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 73) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 6, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_112, tvbrange, value) - tvbrange = padded(offset + 137, 1) + subtree = tree:add_le(f.RADIO_RC_CHANNELS_target_system, tvbrange, value) + tvbrange = padded(offset + 7, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_113, tvbrange, value) - tvbrange = padded(offset + 138, 1) + subtree = tree:add_le(f.RADIO_RC_CHANNELS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_114, tvbrange, value) - tvbrange = padded(offset + 139, 1) + subtree = tree:add_le(f.RADIO_RC_CHANNELS_time_last_update_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_115, tvbrange, value) - tvbrange = padded(offset + 140, 1) + subtree = tree:add_le(f.RADIO_RC_CHANNELS_flags, tvbrange, value) + dissect_flags_RADIO_RC_CHANNELS_FLAGS(subtree, "RADIO_RC_CHANNELS_flags", tvbrange, value) + tvbrange = padded(offset + 8, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_116, tvbrange, value) - tvbrange = padded(offset + 141, 1) + subtree = tree:add_le(f.RADIO_RC_CHANNELS_count, tvbrange, value) + tvbrange = padded(offset + 9, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_0, tvbrange, value) + tvbrange = padded(offset + 11, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_1, tvbrange, value) + tvbrange = padded(offset + 13, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_2, tvbrange, value) + tvbrange = padded(offset + 15, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_3, tvbrange, value) + tvbrange = padded(offset + 17, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_4, tvbrange, value) + tvbrange = padded(offset + 19, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_5, tvbrange, value) + tvbrange = padded(offset + 21, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_6, tvbrange, value) + tvbrange = padded(offset + 23, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_7, tvbrange, value) + tvbrange = padded(offset + 25, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_8, tvbrange, value) + tvbrange = padded(offset + 27, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_9, tvbrange, value) + tvbrange = padded(offset + 29, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_10, tvbrange, value) + tvbrange = padded(offset + 31, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_11, tvbrange, value) + tvbrange = padded(offset + 33, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_12, tvbrange, value) + tvbrange = padded(offset + 35, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_13, tvbrange, value) + tvbrange = padded(offset + 37, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_14, tvbrange, value) + tvbrange = padded(offset + 39, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_15, tvbrange, value) + tvbrange = padded(offset + 41, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_16, tvbrange, value) + tvbrange = padded(offset + 43, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_17, tvbrange, value) + tvbrange = padded(offset + 45, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_18, tvbrange, value) + tvbrange = padded(offset + 47, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_19, tvbrange, value) + tvbrange = padded(offset + 49, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_20, tvbrange, value) + tvbrange = padded(offset + 51, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_21, tvbrange, value) + tvbrange = padded(offset + 53, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_22, tvbrange, value) + tvbrange = padded(offset + 55, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_23, tvbrange, value) + tvbrange = padded(offset + 57, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_24, tvbrange, value) + tvbrange = padded(offset + 59, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_25, tvbrange, value) + tvbrange = padded(offset + 61, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_26, tvbrange, value) + tvbrange = padded(offset + 63, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_27, tvbrange, value) + tvbrange = padded(offset + 65, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_28, tvbrange, value) + tvbrange = padded(offset + 67, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_29, tvbrange, value) + tvbrange = padded(offset + 69, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_30, tvbrange, value) + tvbrange = padded(offset + 71, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RADIO_RC_CHANNELS_channels_31, tvbrange, value) +end +-- dissect payload of message type AVAILABLE_MODES +function payload_fns.payload_435(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 46 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 46) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 8, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_117, tvbrange, value) - tvbrange = padded(offset + 142, 1) + subtree = tree:add_le(f.AVAILABLE_MODES_number_modes, tvbrange, value) + tvbrange = padded(offset + 9, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_118, tvbrange, value) - tvbrange = padded(offset + 143, 1) + subtree = tree:add_le(f.AVAILABLE_MODES_mode_index, tvbrange, value) + tvbrange = padded(offset + 10, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_119, tvbrange, value) - tvbrange = padded(offset + 144, 1) + subtree = tree:add_le(f.AVAILABLE_MODES_standard_mode, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_120, tvbrange, value) - tvbrange = padded(offset + 145, 1) + subtree = tree:add_le(f.AVAILABLE_MODES_custom_mode, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_121, tvbrange, value) - tvbrange = padded(offset + 146, 1) + subtree = tree:add_le(f.AVAILABLE_MODES_properties, tvbrange, value) + dissect_flags_MAV_MODE_PROPERTY(subtree, "AVAILABLE_MODES_properties", tvbrange, value) + tvbrange = padded(offset + 11, 35) + value = tvbrange:string() + subtree = tree:add_le(f.AVAILABLE_MODES_mode_name, tvbrange, value) +end +-- dissect payload of message type CURRENT_MODE +function payload_fns.payload_436(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 9 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 9) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 8, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_122, tvbrange, value) - tvbrange = padded(offset + 147, 1) + subtree = tree:add_le(f.CURRENT_MODE_standard_mode, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_123, tvbrange, value) - tvbrange = padded(offset + 148, 1) + subtree = tree:add_le(f.CURRENT_MODE_custom_mode, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_124, tvbrange, value) - tvbrange = padded(offset + 149, 1) + subtree = tree:add_le(f.CURRENT_MODE_intended_custom_mode, tvbrange, value) +end +-- dissect payload of message type AVAILABLE_MODES_MONITOR +function payload_fns.payload_437(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.OPEN_DRONE_ID_MESSAGE_PACK_messages_125, tvbrange, value) - tvbrange = padded(offset + 150, 1) + subtree = tree:add_le(f.AVAILABLE_MODES_MONITOR_seq, tvbrange, value) +end +-- dissect payload of message type GNSS_INTEGRITY +function payload_fns.payload_441(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 17 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 17) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 8, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_126, tvbrange, value) - tvbrange = padded(offset + 151, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_127, tvbrange, value) - tvbrange = padded(offset + 152, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_system_errors, tvbrange, value) + dissect_flags_GPS_SYSTEM_ERROR_FLAGS(subtree, "GNSS_INTEGRITY_system_errors", tvbrange, value) + tvbrange = padded(offset + 9, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_128, tvbrange, value) - tvbrange = padded(offset + 153, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_authentication_state, tvbrange, value) + tvbrange = padded(offset + 10, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_129, tvbrange, value) - tvbrange = padded(offset + 154, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_jamming_state, tvbrange, value) + tvbrange = padded(offset + 11, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_130, tvbrange, value) - tvbrange = padded(offset + 155, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_spoofing_state, tvbrange, value) + tvbrange = padded(offset + 12, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_131, tvbrange, value) - tvbrange = padded(offset + 156, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_raim_state, tvbrange, value) + tvbrange = padded(offset + 4, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_132, tvbrange, value) - tvbrange = padded(offset + 157, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_raim_hfom, tvbrange, value) + tvbrange = padded(offset + 6, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_133, tvbrange, value) - tvbrange = padded(offset + 158, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_raim_vfom, tvbrange, value) + tvbrange = padded(offset + 13, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_134, tvbrange, value) - tvbrange = padded(offset + 159, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_corrections_quality, tvbrange, value) + tvbrange = padded(offset + 14, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_135, tvbrange, value) - tvbrange = padded(offset + 160, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_system_status_summary, tvbrange, value) + tvbrange = padded(offset + 15, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_136, tvbrange, value) - tvbrange = padded(offset + 161, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_gnss_signal_quality, tvbrange, value) + tvbrange = padded(offset + 16, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_137, tvbrange, value) - tvbrange = padded(offset + 162, 1) + subtree = tree:add_le(f.GNSS_INTEGRITY_post_processing_quality, tvbrange, value) +end +-- dissect payload of message type ICAROUS_HEARTBEAT +function payload_fns.payload_42000(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.OPEN_DRONE_ID_MESSAGE_PACK_messages_138, tvbrange, value) - tvbrange = padded(offset + 163, 1) + subtree = tree:add_le(f.ICAROUS_HEARTBEAT_status, tvbrange, value) +end +-- dissect payload of message type ICAROUS_KINEMATIC_BANDS +function payload_fns.payload_42001(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 46 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 46) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_numBands, tvbrange, value) + tvbrange = padded(offset + 41, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_139, tvbrange, value) - tvbrange = padded(offset + 164, 1) + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type1, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max1, tvbrange, value) + tvbrange = padded(offset + 42, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_140, tvbrange, value) - tvbrange = padded(offset + 165, 1) + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max2, tvbrange, value) + tvbrange = padded(offset + 43, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_141, tvbrange, value) - tvbrange = padded(offset + 166, 1) + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max3, tvbrange, value) + tvbrange = padded(offset + 44, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_142, tvbrange, value) - tvbrange = padded(offset + 167, 1) + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type4, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max4, tvbrange, value) + tvbrange = padded(offset + 45, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_143, tvbrange, value) - tvbrange = padded(offset + 168, 1) + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type5, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min5, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max5, 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 + if (offset + 9 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 9) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 4, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_144, tvbrange, value) - tvbrange = padded(offset + 169, 1) + subtree = tree:add_le(f.HEARTBEAT_type, tvbrange, value) + tvbrange = padded(offset + 5, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_145, tvbrange, value) - tvbrange = padded(offset + 170, 1) + subtree = tree:add_le(f.HEARTBEAT_autopilot, tvbrange, value) + tvbrange = padded(offset + 6, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_146, tvbrange, value) - tvbrange = padded(offset + 171, 1) + subtree = tree:add_le(f.HEARTBEAT_base_mode, tvbrange, value) + dissect_flags_MAV_MODE_FLAG(subtree, "HEARTBEAT_base_mode", tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_147, tvbrange, value) - tvbrange = padded(offset + 172, 1) + subtree = tree:add_le(f.HEARTBEAT_custom_mode, tvbrange, value) + tvbrange = padded(offset + 7, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_148, tvbrange, value) - tvbrange = padded(offset + 173, 1) + subtree = tree:add_le(f.HEARTBEAT_system_status, tvbrange, value) + tvbrange = padded(offset + 8, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_149, tvbrange, value) - tvbrange = padded(offset + 174, 1) + subtree = tree:add_le(f.HEARTBEAT_mavlink_version, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_0 +function payload_fns.payload_17150(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 24, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_150, tvbrange, value) - tvbrange = padded(offset + 175, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_v1, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_0_ar_i8_0, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_0_ar_i8_1, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_0_ar_i8_2, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_0_ar_i8_3, tvbrange, value) + tvbrange = padded(offset + 29, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_151, tvbrange, value) - tvbrange = padded(offset + 176, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u8_0, tvbrange, value) + tvbrange = padded(offset + 30, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_152, tvbrange, value) - tvbrange = padded(offset + 177, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u8_1, tvbrange, value) + tvbrange = padded(offset + 31, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_153, tvbrange, value) - tvbrange = padded(offset + 178, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u8_2, tvbrange, value) + tvbrange = padded(offset + 32, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_154, tvbrange, value) - tvbrange = padded(offset + 179, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u8_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_155, tvbrange, value) - tvbrange = padded(offset + 180, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u16_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_156, tvbrange, value) - tvbrange = padded(offset + 181, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u16_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_157, tvbrange, value) - tvbrange = padded(offset + 182, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u16_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_158, tvbrange, value) - tvbrange = padded(offset + 183, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u16_3, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_159, tvbrange, value) - tvbrange = padded(offset + 184, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u32_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_160, tvbrange, value) - tvbrange = padded(offset + 185, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u32_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_161, tvbrange, value) - tvbrange = padded(offset + 186, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u32_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_162, tvbrange, value) - tvbrange = padded(offset + 187, 1) + subtree = tree:add_le(f.ARRAY_TEST_0_ar_u32_3, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_1 +function payload_fns.payload_17151(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 16 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 16) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_163, tvbrange, value) - tvbrange = padded(offset + 188, 1) + subtree = tree:add_le(f.ARRAY_TEST_1_ar_u32_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_164, tvbrange, value) - tvbrange = padded(offset + 189, 1) + subtree = tree:add_le(f.ARRAY_TEST_1_ar_u32_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_165, tvbrange, value) - tvbrange = padded(offset + 190, 1) + subtree = tree:add_le(f.ARRAY_TEST_1_ar_u32_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_166, tvbrange, value) - tvbrange = padded(offset + 191, 1) + subtree = tree:add_le(f.ARRAY_TEST_1_ar_u32_3, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_3 +function payload_fns.payload_17153(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 17 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 17) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 16, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_167, tvbrange, value) - tvbrange = padded(offset + 192, 1) + subtree = tree:add_le(f.ARRAY_TEST_3_v, tvbrange, value) + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_168, tvbrange, value) - tvbrange = padded(offset + 193, 1) + subtree = tree:add_le(f.ARRAY_TEST_3_ar_u32_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_169, tvbrange, value) - tvbrange = padded(offset + 194, 1) + subtree = tree:add_le(f.ARRAY_TEST_3_ar_u32_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_170, tvbrange, value) - tvbrange = padded(offset + 195, 1) + subtree = tree:add_le(f.ARRAY_TEST_3_ar_u32_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_171, tvbrange, value) - tvbrange = padded(offset + 196, 1) + subtree = tree:add_le(f.ARRAY_TEST_3_ar_u32_3, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_4 +function payload_fns.payload_17154(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 17 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 17) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_172, tvbrange, value) - tvbrange = padded(offset + 197, 1) + subtree = tree:add_le(f.ARRAY_TEST_4_ar_u32_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_173, tvbrange, value) - tvbrange = padded(offset + 198, 1) + subtree = tree:add_le(f.ARRAY_TEST_4_ar_u32_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_174, tvbrange, value) - tvbrange = padded(offset + 199, 1) + subtree = tree:add_le(f.ARRAY_TEST_4_ar_u32_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_175, tvbrange, value) - tvbrange = padded(offset + 200, 1) + subtree = tree:add_le(f.ARRAY_TEST_4_ar_u32_3, tvbrange, value) + tvbrange = padded(offset + 16, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_176, tvbrange, value) - tvbrange = padded(offset + 201, 1) + subtree = tree:add_le(f.ARRAY_TEST_4_v, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_5 +function payload_fns.payload_17155(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 10 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 10) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 5) + value = tvbrange:string() + subtree = tree:add_le(f.ARRAY_TEST_5_c1, tvbrange, value) + tvbrange = padded(offset + 5, 5) + value = tvbrange:string() + subtree = tree:add_le(f.ARRAY_TEST_5_c2, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_6 +function payload_fns.payload_17156(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 91 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 91) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 54, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_177, tvbrange, value) - tvbrange = padded(offset + 202, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_v1, tvbrange, value) + tvbrange = padded(offset + 44, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_178, tvbrange, value) - tvbrange = padded(offset + 203, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_v2, tvbrange, value) + tvbrange = padded(offset + 16, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_179, tvbrange, value) - tvbrange = padded(offset + 204, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_v3, tvbrange, value) + tvbrange = padded(offset + 20, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_180, tvbrange, value) - tvbrange = padded(offset + 205, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_ar_u32_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_181, tvbrange, value) - tvbrange = padded(offset + 206, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_ar_u32_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_i32_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_i32_1, tvbrange, value) + tvbrange = padded(offset + 46, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_182, tvbrange, value) - tvbrange = padded(offset + 207, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_ar_u16_0, tvbrange, value) + tvbrange = padded(offset + 48, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_183, tvbrange, value) - tvbrange = padded(offset + 208, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_ar_u16_1, tvbrange, value) + tvbrange = padded(offset + 50, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_i16_0, tvbrange, value) + tvbrange = padded(offset + 52, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_i16_1, tvbrange, value) + tvbrange = padded(offset + 55, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_184, tvbrange, value) - tvbrange = padded(offset + 209, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_ar_u8_0, tvbrange, value) + tvbrange = padded(offset + 56, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_185, tvbrange, value) - tvbrange = padded(offset + 210, 1) + subtree = tree:add_le(f.ARRAY_TEST_6_ar_u8_1, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_i8_0, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_i8_1, tvbrange, value) + tvbrange = padded(offset + 59, 32) + value = tvbrange:string() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_c, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_d_0, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_d_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_f_0, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ARRAY_TEST_6_ar_f_1, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_7 +function payload_fns.payload_17157(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 84 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 84) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_d_0, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_d_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_f_0, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_f_1, tvbrange, value) + tvbrange = padded(offset + 24, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_186, tvbrange, value) - tvbrange = padded(offset + 211, 1) + subtree = tree:add_le(f.ARRAY_TEST_7_ar_u32_0, tvbrange, value) + tvbrange = padded(offset + 28, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_187, tvbrange, value) - tvbrange = padded(offset + 212, 1) + subtree = tree:add_le(f.ARRAY_TEST_7_ar_u32_1, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_i32_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_i32_1, tvbrange, value) + tvbrange = padded(offset + 40, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_188, tvbrange, value) - tvbrange = padded(offset + 213, 1) + subtree = tree:add_le(f.ARRAY_TEST_7_ar_u16_0, tvbrange, value) + tvbrange = padded(offset + 42, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_189, tvbrange, value) - tvbrange = padded(offset + 214, 1) + subtree = tree:add_le(f.ARRAY_TEST_7_ar_u16_1, tvbrange, value) + tvbrange = padded(offset + 44, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_i16_0, tvbrange, value) + tvbrange = padded(offset + 46, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_i16_1, tvbrange, value) + tvbrange = padded(offset + 48, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_190, tvbrange, value) - tvbrange = padded(offset + 215, 1) + subtree = tree:add_le(f.ARRAY_TEST_7_ar_u8_0, tvbrange, value) + tvbrange = padded(offset + 49, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_191, tvbrange, value) - tvbrange = padded(offset + 216, 1) + subtree = tree:add_le(f.ARRAY_TEST_7_ar_u8_1, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_i8_0, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_i8_1, tvbrange, value) + tvbrange = padded(offset + 52, 32) + value = tvbrange:string() + subtree = tree:add_le(f.ARRAY_TEST_7_ar_c, tvbrange, value) +end +-- dissect payload of message type ARRAY_TEST_8 +function payload_fns.payload_17158(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 24 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 24) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 16, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_192, tvbrange, value) - tvbrange = padded(offset + 217, 1) + subtree = tree:add_le(f.ARRAY_TEST_8_v3, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.ARRAY_TEST_8_ar_d_0, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.ARRAY_TEST_8_ar_d_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_193, tvbrange, value) - tvbrange = padded(offset + 218, 1) + subtree = tree:add_le(f.ARRAY_TEST_8_ar_u16_0, tvbrange, value) + tvbrange = padded(offset + 22, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_194, tvbrange, value) - tvbrange = padded(offset + 219, 1) + subtree = tree:add_le(f.ARRAY_TEST_8_ar_u16_1, tvbrange, value) +end +-- dissect payload of message type TEST_TYPES +function payload_fns.payload_17000(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 179 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 179) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 160, 1) + value = tvbrange:string() + subtree = tree:add_le(f.TEST_TYPES_c, tvbrange, value) + tvbrange = padded(offset + 161, 10) + value = tvbrange:string() + subtree = tree:add_le(f.TEST_TYPES_s, tvbrange, value) + tvbrange = padded(offset + 171, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_195, tvbrange, value) - tvbrange = padded(offset + 220, 1) + subtree = tree:add_le(f.TEST_TYPES_u8, tvbrange, value) + tvbrange = padded(offset + 144, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_196, tvbrange, value) - tvbrange = padded(offset + 221, 1) + subtree = tree:add_le(f.TEST_TYPES_u16, tvbrange, value) + tvbrange = padded(offset + 96, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_197, tvbrange, value) - tvbrange = padded(offset + 222, 1) + subtree = tree:add_le(f.TEST_TYPES_u32, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TEST_TYPES_u64, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s8, tvbrange, value) + tvbrange = padded(offset + 146, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s32, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_int64() + subtree = tree:add_le(f.TEST_TYPES_s64, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TEST_TYPES_f, tvbrange, value) + tvbrange = padded(offset + 16, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.TEST_TYPES_d, tvbrange, value) + tvbrange = padded(offset + 173, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_198, tvbrange, value) - tvbrange = padded(offset + 223, 1) + subtree = tree:add_le(f.TEST_TYPES_u8_array_0, tvbrange, value) + tvbrange = padded(offset + 174, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_199, tvbrange, value) - tvbrange = padded(offset + 224, 1) + subtree = tree:add_le(f.TEST_TYPES_u8_array_1, tvbrange, value) + tvbrange = padded(offset + 175, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_200, tvbrange, value) - tvbrange = padded(offset + 225, 1) + subtree = tree:add_le(f.TEST_TYPES_u8_array_2, tvbrange, value) + tvbrange = padded(offset + 148, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_201, tvbrange, value) - tvbrange = padded(offset + 226, 1) + subtree = tree:add_le(f.TEST_TYPES_u16_array_0, tvbrange, value) + tvbrange = padded(offset + 150, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_202, tvbrange, value) - tvbrange = padded(offset + 227, 1) + subtree = tree:add_le(f.TEST_TYPES_u16_array_1, tvbrange, value) + tvbrange = padded(offset + 152, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_203, tvbrange, value) - tvbrange = padded(offset + 228, 1) + subtree = tree:add_le(f.TEST_TYPES_u16_array_2, tvbrange, value) + tvbrange = padded(offset + 108, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_204, tvbrange, value) - tvbrange = padded(offset + 229, 1) + subtree = tree:add_le(f.TEST_TYPES_u32_array_0, tvbrange, value) + tvbrange = padded(offset + 112, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_205, tvbrange, value) - tvbrange = padded(offset + 230, 1) + subtree = tree:add_le(f.TEST_TYPES_u32_array_1, tvbrange, value) + tvbrange = padded(offset + 116, 4) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_206, tvbrange, value) - tvbrange = padded(offset + 231, 1) + subtree = tree:add_le(f.TEST_TYPES_u32_array_2, tvbrange, value) + tvbrange = padded(offset + 24, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TEST_TYPES_u64_array_0, tvbrange, value) + tvbrange = padded(offset + 32, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TEST_TYPES_u64_array_1, tvbrange, value) + tvbrange = padded(offset + 40, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TEST_TYPES_u64_array_2, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s8_array_0, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s8_array_1, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s8_array_2, tvbrange, value) + tvbrange = padded(offset + 154, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s16_array_0, tvbrange, value) + tvbrange = padded(offset + 156, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s16_array_1, tvbrange, value) + tvbrange = padded(offset + 158, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s16_array_2, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s32_array_0, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s32_array_1, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TEST_TYPES_s32_array_2, tvbrange, value) + tvbrange = padded(offset + 48, 8) + value = tvbrange:le_int64() + subtree = tree:add_le(f.TEST_TYPES_s64_array_0, tvbrange, value) + tvbrange = padded(offset + 56, 8) + value = tvbrange:le_int64() + subtree = tree:add_le(f.TEST_TYPES_s64_array_1, tvbrange, value) + tvbrange = padded(offset + 64, 8) + value = tvbrange:le_int64() + subtree = tree:add_le(f.TEST_TYPES_s64_array_2, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TEST_TYPES_f_array_0, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TEST_TYPES_f_array_1, tvbrange, value) + tvbrange = padded(offset + 140, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TEST_TYPES_f_array_2, tvbrange, value) + tvbrange = padded(offset + 72, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.TEST_TYPES_d_array_0, tvbrange, value) + tvbrange = padded(offset + 80, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.TEST_TYPES_d_array_1, tvbrange, value) + tvbrange = padded(offset + 88, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.TEST_TYPES_d_array_2, tvbrange, value) +end +-- dissect payload of message type NAV_FILTER_BIAS +function payload_fns.payload_220(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 32 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 32) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.NAV_FILTER_BIAS_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_FILTER_BIAS_accel_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_FILTER_BIAS_accel_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_FILTER_BIAS_accel_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_FILTER_BIAS_gyro_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_FILTER_BIAS_gyro_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_FILTER_BIAS_gyro_2, tvbrange, value) +end +-- dissect payload of message type RADIO_CALIBRATION +function payload_fns.payload_221(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 42 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 42) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_207, tvbrange, value) - tvbrange = padded(offset + 232, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_aileron_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_208, tvbrange, value) - tvbrange = padded(offset + 233, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_aileron_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_209, tvbrange, value) - tvbrange = padded(offset + 234, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_aileron_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_210, tvbrange, value) - tvbrange = padded(offset + 235, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_elevator_0, tvbrange, value) + tvbrange = padded(offset + 8, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_211, tvbrange, value) - tvbrange = padded(offset + 236, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_elevator_1, tvbrange, value) + tvbrange = padded(offset + 10, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_212, tvbrange, value) - tvbrange = padded(offset + 237, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_elevator_2, tvbrange, value) + tvbrange = padded(offset + 12, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_213, tvbrange, value) - tvbrange = padded(offset + 238, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_rudder_0, tvbrange, value) + tvbrange = padded(offset + 14, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_214, tvbrange, value) - tvbrange = padded(offset + 239, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_rudder_1, tvbrange, value) + tvbrange = padded(offset + 16, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_215, tvbrange, value) - tvbrange = padded(offset + 240, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_rudder_2, tvbrange, value) + tvbrange = padded(offset + 18, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_216, tvbrange, value) - tvbrange = padded(offset + 241, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_gyro_0, tvbrange, value) + tvbrange = padded(offset + 20, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_217, tvbrange, value) - tvbrange = padded(offset + 242, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_gyro_1, tvbrange, value) + tvbrange = padded(offset + 22, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_218, tvbrange, value) - tvbrange = padded(offset + 243, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_pitch_0, tvbrange, value) + tvbrange = padded(offset + 24, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_219, tvbrange, value) - tvbrange = padded(offset + 244, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_pitch_1, tvbrange, value) + tvbrange = padded(offset + 26, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_220, tvbrange, value) - tvbrange = padded(offset + 245, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_pitch_2, tvbrange, value) + tvbrange = padded(offset + 28, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_221, tvbrange, value) - tvbrange = padded(offset + 246, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_pitch_3, tvbrange, value) + tvbrange = padded(offset + 30, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_222, tvbrange, value) - tvbrange = padded(offset + 247, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_pitch_4, tvbrange, value) + tvbrange = padded(offset + 32, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_223, tvbrange, value) - tvbrange = padded(offset + 248, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_throttle_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_224, tvbrange, value) -end --- dissect payload of message type OPEN_DRONE_ID_SYSTEM_UPDATE -function payload_fns.payload_12919(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 18 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 18) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 16, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_throttle_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_system, tvbrange, value) - tvbrange = padded(offset + 17, 1) + subtree = tree:add_le(f.RADIO_CALIBRATION_throttle_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_component, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_latitude, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_int() - subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_longitude, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_altitude_geo, tvbrange, value) - tvbrange = padded(offset + 12, 4) + subtree = tree:add_le(f.RADIO_CALIBRATION_throttle_3, tvbrange, value) + tvbrange = padded(offset + 40, 2) value = tvbrange:le_uint() - subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_timestamp, tvbrange, value) + subtree = tree:add_le(f.RADIO_CALIBRATION_throttle_4, tvbrange, value) end --- dissect payload of message type HYGROMETER_SENSOR -function payload_fns.payload_12920(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type UALBERTA_SYS_STATUS +function payload_fns.payload_222(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 5 > limit) then + if (offset + 3 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 5) + padded:set_size(offset + 3) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 4, 1) + tvbrange = padded(offset + 0, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.HYGROMETER_SENSOR_id, tvbrange, value) - tvbrange = padded(offset + 0, 2) - value = tvbrange:le_int() - subtree = tree:add_le(f.HYGROMETER_SENSOR_temperature, tvbrange, value) - tvbrange = padded(offset + 2, 2) + subtree = tree:add_le(f.UALBERTA_SYS_STATUS_mode, tvbrange, value) + tvbrange = padded(offset + 1, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.HYGROMETER_SENSOR_humidity, tvbrange, value) + subtree = tree:add_le(f.UALBERTA_SYS_STATUS_nav_mode, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UALBERTA_SYS_STATUS_pilot, tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_CFG function payload_fns.payload_10001(buffer, tree, msgid, offset, limit, pinfo) @@ -52571,79 +57358,6 @@ function payload_fns.payload_10008(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:string() subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_flight_id, tvbrange, value) end --- dissect payload of message type ICAROUS_HEARTBEAT -function payload_fns.payload_42000(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.ICAROUS_HEARTBEAT_status, tvbrange, value) -end --- dissect payload of message type ICAROUS_KINEMATIC_BANDS -function payload_fns.payload_42001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree, tvbrange - if (offset + 46 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 46) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 40, 1) - value = tvbrange:le_int() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_numBands, tvbrange, value) - tvbrange = padded(offset + 41, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type1, tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min1, tvbrange, value) - tvbrange = padded(offset + 4, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max1, tvbrange, value) - tvbrange = padded(offset + 42, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type2, tvbrange, value) - tvbrange = padded(offset + 8, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min2, tvbrange, value) - tvbrange = padded(offset + 12, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max2, tvbrange, value) - tvbrange = padded(offset + 43, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type3, tvbrange, value) - tvbrange = padded(offset + 16, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min3, tvbrange, value) - tvbrange = padded(offset + 20, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max3, tvbrange, value) - tvbrange = padded(offset + 44, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type4, tvbrange, value) - tvbrange = padded(offset + 24, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min4, tvbrange, value) - tvbrange = padded(offset + 28, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max4, tvbrange, value) - tvbrange = padded(offset + 45, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type5, tvbrange, value) - tvbrange = padded(offset + 32, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min5, tvbrange, value) - tvbrange = padded(offset + 36, 4) - value = tvbrange:le_float() - subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max5, tvbrange, value) -end -- dissect payload of message type LOWEHEISER_GOV_EFI function payload_fns.payload_10151(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -52724,6 +57438,525 @@ function payload_fns.payload_10151(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_status, tvbrange, value) end +-- dissect payload of message type STORM32_GIMBAL_DEVICE_STATUS +function payload_fns.payload_60001(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 42 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 42) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_target_system, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "STORM32_GIMBAL_DEVICE_STATUS_flags", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_angular_velocity_z, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_yaw_absolute, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_STATUS_failure_flags, tvbrange, value) + dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(subtree, "STORM32_GIMBAL_DEVICE_STATUS_failure_flags", tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_DEVICE_CONTROL +function payload_fns.payload_60002(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 32 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 32) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "STORM32_GIMBAL_DEVICE_CONTROL_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_q_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_q_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_q_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_q_3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_DEVICE_CONTROL_angular_velocity_z, tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_MANAGER_INFORMATION +function payload_fns.payload_60010(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_gimbal_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_INFORMATION_device_cap_flags", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_INFORMATION_manager_cap_flags", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_roll_min, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_roll_max, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_pitch_min, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_pitch_max, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_yaw_min, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_INFORMATION_yaw_max, tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_MANAGER_STATUS +function payload_fns.payload_60011(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 7 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 7) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_STATUS_gimbal_id, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_STATUS_supervisor, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_STATUS_device_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_STATUS_device_flags", tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_STATUS_manager_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_STATUS_manager_flags", tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_STATUS_profile, tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_MANAGER_CONTROL +function payload_fns.payload_60012(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 36 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 36) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_target_component, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_gimbal_id, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_client, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_device_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_CONTROL_device_flags", tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_manager_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_CONTROL_manager_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_q_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_q_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_q_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_q_3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_angular_velocity_z, tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW +function payload_fns.payload_60013(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 24 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 24) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_target_system, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_target_component, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_gimbal_id, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_client, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_DEVICE_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_device_flags", tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags, tvbrange, value) + dissect_flags_MAV_STORM32_GIMBAL_MANAGER_FLAGS(subtree, "STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_manager_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_pitch, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_yaw, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_yaw_rate, tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_MANAGER_CORRECT_ROLL +function payload_fns.payload_60014(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 + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_target_component, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_gimbal_id, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_client, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_CORRECT_ROLL_roll, tvbrange, value) +end +-- dissect payload of message type STORM32_GIMBAL_MANAGER_PROFILE +function payload_fns.payload_60015(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 22 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 22) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_gimbal_id, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_profile, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_0, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_1, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_2, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_3, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_4, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_5, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_6, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_priorities_7, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_profile_flags, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_rc_timeout, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_0, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_1, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_2, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_3, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_4, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_5, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_6, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORM32_GIMBAL_MANAGER_PROFILE_timeouts_7, tvbrange, value) +end +-- dissect payload of message type QSHOT_STATUS +function payload_fns.payload_60020(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 4 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 4) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.QSHOT_STATUS_mode, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.QSHOT_STATUS_shot_state, tvbrange, value) +end +-- dissect payload of message type COMPONENT_PREARM_STATUS +function payload_fns.payload_60025(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 10 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 10) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMPONENT_PREARM_STATUS_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMPONENT_PREARM_STATUS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMPONENT_PREARM_STATUS_enabled_flags, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMPONENT_PREARM_STATUS_fail_flags, tvbrange, value) +end +-- dissect payload of message type AVSS_PRS_SYS_STATUS +function payload_fns.payload_60050(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 14 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 14) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_PRS_SYS_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_PRS_SYS_STATUS_error_status, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_PRS_SYS_STATUS_battery_status, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_PRS_SYS_STATUS_arm_status, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_PRS_SYS_STATUS_charge_status, tvbrange, value) +end +-- dissect payload of message type AVSS_DRONE_POSITION +function payload_fns.payload_60051(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 24 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 24) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_DRONE_POSITION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AVSS_DRONE_POSITION_lat, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AVSS_DRONE_POSITION_lon, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AVSS_DRONE_POSITION_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_POSITION_ground_alt, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_POSITION_barometer_alt, tvbrange, value) +end +-- dissect payload of message type AVSS_DRONE_IMU +function payload_fns.payload_60052(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 44 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 44) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_DRONE_IMU_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_q1, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_q2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_q3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_q4, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_xacc, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_yacc, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_zacc, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_xgyro, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_ygyro, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AVSS_DRONE_IMU_zgyro, tvbrange, value) +end +-- dissect payload of message type AVSS_DRONE_OPERATION_MODE +function payload_fns.payload_60053(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 6 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 6) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_DRONE_OPERATION_MODE_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_DRONE_OPERATION_MODE_M300_operation_mode, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AVSS_DRONE_OPERATION_MODE_horsefly_operation_mode, tvbrange, value) +end -- dissect payload of message type CUBEPILOT_RAW_RC function payload_fns.payload_50001(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -52972,36 +58205,6 @@ function payload_fns.payload_52001(buffer, tree, msgid, offset, limit, pinfo) 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 - if (offset + 9 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 9) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - tvbrange = padded(offset + 4, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HEARTBEAT_type, tvbrange, value) - tvbrange = padded(offset + 5, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HEARTBEAT_autopilot, tvbrange, value) - tvbrange = padded(offset + 6, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HEARTBEAT_base_mode, tvbrange, value) - dissect_flags_MAV_MODE_FLAG(subtree, "HEARTBEAT_base_mode", tvbrange, value) - tvbrange = padded(offset + 0, 4) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HEARTBEAT_custom_mode, tvbrange, value) - tvbrange = padded(offset + 7, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HEARTBEAT_system_status, tvbrange, value) - tvbrange = padded(offset + 8, 1) - value = tvbrange:le_uint() - subtree = tree:add_le(f.HEARTBEAT_mavlink_version, tvbrange, value) -end -- dissector function function mavlink_proto.dissector(buffer,pinfo,tree) local offset = 0 diff --git a/ExtLibs/Mavlink/message_definitions/ASLUAV.xml b/ExtLibs/Mavlink/message_definitions/ASLUAV.xml new file mode 100644 index 0000000000..4e80a5ac78 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/ASLUAV.xml @@ -0,0 +1,294 @@ + + + + + common.xml + + + + + Mission command to reset Maximum Power Point Tracker (MPPT) + MPPT number + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a power cycle on payload + Complete power cycle + VISensor power cycle + Empty + Empty + Empty + Empty + Empty + + + + + no service + + + link type unknown + + + 2G (GSM/GRPS/EDGE) link + + + 3G link (WCDMA/HSDPA/HSPA) + + + 4G link (LTE) + + + + + not specified + + + HUAWEI LTE USB Stick E3372 + + + + + + Message encoding a command with parameters as scaled integers and additional metadata. Scaling depends on the actual command value. + UTC time, seconds elapsed since 01.01.1970 + Microseconds elapsed since vehicle boot + System ID + Component ID + The coordinate system of the COMMAND, as defined by MAV_FRAME enum + The scheduled action for the mission item, as defined by MAV_CMD enum + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + PARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame). + + + Send a command with up to seven parameters to the MAV and additional metadata + UTC time, seconds elapsed since 01.01.1970 + Microseconds elapsed since vehicle boot + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + Parameter 5, as defined by MAV_CMD enum. + Parameter 6, as defined by MAV_CMD enum. + Parameter 7, as defined by MAV_CMD enum. + + + Voltage and current sensor data + Power board voltage sensor reading + Power board current sensor reading + Board current sensor 1 reading + Board current sensor 2 reading + + + Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking + MPPT last timestamp + MPPT1 voltage + MPPT1 current + MPPT1 pwm + MPPT1 status + MPPT2 voltage + MPPT2 current + MPPT2 pwm + MPPT2 status + MPPT3 voltage + MPPT3 current + MPPT3 pwm + MPPT3 status + + + ASL-fixed-wing controller data + Timestamp + ASLCTRL control-mode (manual, stabilized, auto, etc...) + See sourcecode for a description of these values... + + + Pitch angle + Pitch angle reference + + + + + + + Airspeed reference + + Yaw angle + Yaw angle reference + Roll angle + Roll angle reference + + + + + + + + + ASL-fixed-wing controller debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + + + Extended state information for ASLUAVs + Status of the position-indicator LEDs + Status of the IRIDIUM satellite communication system + Status vector for up to 8 servos + Motor RPM + + + + Extended EKF state estimates for ASLUAVs + Time since system start + Magnitude of wind velocity (in lateral inertial plane) + Wind heading angle from North + Z (Down) component of inertial wind velocity + Magnitude of air velocity + Sideslip angle + Angle of attack + + + Off-board controls/commands for ASLUAVs + Time since system start + Elevator command [~] + Throttle command [~] + Throttle 2 command [~] + Left aileron command [~] + Right aileron command [~] + Rudder command [~] + Off-board computer status + + + Atmospheric sensors (temperature, humidity, ...) + Time since system boot + Ambient temperature + Relative humidity + + + Battery pack monitoring data for Li-Ion batteries + Time since system start + Battery pack temperature + Battery pack voltage + Battery pack current + Battery pack state-of-charge + Battery monitor status report bits in Hex + Battery monitor serial number in Hex + Battery monitor safetystatus report bits in Hex + Battery monitor operation status report bits in Hex + Battery pack cell 1 voltage + Battery pack cell 2 voltage + Battery pack cell 3 voltage + Battery pack cell 4 voltage + Battery pack cell 5 voltage + Battery pack cell 6 voltage + + + Fixed-wing soaring (i.e. thermal seeking) data + Timestamp + Timestamp since last mode change + Thermal core updraft strength + Thermal radius + Thermal center latitude + Thermal center longitude + Variance W + Variance R + Variance Lat + Variance Lon + Suggested loiter radius + Suggested loiter direction + Distance to soar point + Expected sink rate at current airspeed, roll and throttle + Measurement / updraft speed at current/local airplane position + Measurement / roll angle tracking error + Expected measurement 1 + Expected measurement 2 + Thermal drift (from estimator prediction step only) + Thermal drift (from estimator prediction step only) + Total specific energy change (filtered) + Debug variable 1 + Debug variable 2 + Control Mode [-] + Data valid [-] + + + Monitoring of sensorpod status + Timestamp in linuxtime (since 1.1.1970) + Rate of ROS topic 1 + Rate of ROS topic 2 + Rate of ROS topic 3 + Rate of ROS topic 4 + Number of recording nodes + Temperature of sensorpod CPU in + Free space available in recordings directory in [Gb] * 1e2 + + + Monitoring of power board status + Timestamp + Power board status register + Power board leds status + Power board system voltage + Power board servo voltage + Power board digital voltage + Power board left motor current sensor + Power board right motor current sensor + Power board analog current sensor + Power board digital current sensor + Power board extension current sensor + Power board aux current sensor + + + Status of GSM modem (connected to onboard computer) + Timestamp (of OBC) + GSM modem used + GSM link type + RSSI as reported by modem (unconverted) + RSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted) + SINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted) + RSRQ (LTE only) as reported by modem (unconverted) + + + + Status of the SatCom link + Timestamp + Timestamp of the last successful sbd session + Number of failed sessions + Number of successful sessions + Signal quality + Ring call pending + Transmission session pending + Receiving session pending + + + Calibrated airflow angle measurements + Timestamp + Angle of attack + Angle of attack measurement valid + Sideslip angle + Sideslip angle measurement valid + + + diff --git a/ExtLibs/Mavlink/message_definitions/AVSSUAS.xml b/ExtLibs/Mavlink/message_definitions/AVSSUAS.xml new file mode 100644 index 0000000000..7138758a4c --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/AVSSUAS.xml @@ -0,0 +1,198 @@ + + + + + + + + + common.xml + 2 + 1 + + + + + AVSS defined command. Set PRS arm statuses. + PRS arm statuses + User defined + User defined + User defined + User defined + User defined + User defined + + + AVSS defined command. Gets PRS arm statuses + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + AVSS defined command. Get the PRS battery voltage in millivolts + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + AVSS defined command. Get the PRS error statuses. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + AVSS defined command. Set the ATS arming altitude in meters. + ATS arming altitude + User defined + User defined + User defined + User defined + User defined + User defined + + + AVSS defined command. Get the ATS arming altitude in meters. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + AVSS defined command. Shuts down the PRS system. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + + + AVSS defined command failure reason. PRS not steady. + + + AVSS defined command failure reason. PRS DTM not armed. + + + AVSS defined command failure reason. PRS OTM not armed. + + + + + In manual control mode + + + In attitude mode + + + In GPS mode + + + In hotpoint mode + + + In assisted takeoff mode + + + In auto takeoff mode + + + In auto landing mode + + + In go home mode + + + In sdk control mode + + + In sport mode + + + In force auto landing mode + + + In tripod mode + + + In search mode + + + In engine mode + + + + + In manual control mode + + + In auto takeoff mode + + + In auto landing mode + + + In go home mode + + + In drop mode + + + + + + AVSS PRS system status. + Timestamp (time since PRS boot). + PRS error statuses + Estimated battery run-time without a remote connection and PRS battery voltage + PRS arm statuses + PRS battery charge statuses + + + Drone position. + Timestamp (time since FC boot). + Latitude, expressed + Longitude, expressed + Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. + Altitude above ground, This altitude is measured by a ultrasound, Laser rangefinder or millimeter-wave radar + This altitude is measured by a barometer + + + Drone IMU data. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (time since FC boot). + Quaternion component 1, w (1 in null-rotation) + Quaternion component 2, x (0 in null-rotation) + Quaternion component 3, y (0 in null-rotation) + Quaternion component 4, z (0 in null-rotation) + X acceleration + Y acceleration + Z acceleration + Angular speed around X axis + Angular speed around Y axis + Angular speed around Z axis + + + Drone operation mode. + Timestamp (time since FC boot). + DJI M300 operation mode + horsefly operation mode + + + diff --git a/ExtLibs/Mavlink/message_definitions/all.xml b/ExtLibs/Mavlink/message_definitions/all.xml new file mode 100644 index 0000000000..1c5725258b --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/all.xml @@ -0,0 +1,52 @@ + + + ardupilotmega.xml + + ASLUAV.xml + common.xml + development.xml + icarous.xml + + + minimal.xml + + + python_array_test.xml + standard.xml + test.xml + ualberta.xml + uAvionix.xml + + loweheiser.xml + + storm32.xml + + AVSSUAS.xml + + cubepilot.xml + csAirLink.xml + + + + diff --git a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml index 2bf3091733..3113a615d7 100644 --- a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml +++ b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml @@ -23,6 +23,7 @@ + @@ -1891,4 +1892,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/common.xml b/ExtLibs/Mavlink/message_definitions/common.xml index a38ea14801..a4576e7d95 100644 --- a/ExtLibs/Mavlink/message_definitions/common.xml +++ b/ExtLibs/Mavlink/message_definitions/common.xml @@ -6386,6 +6386,33 @@ Type of estimator that is providing the odometry. Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality + + Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED). + 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. + Number of valid points (up-to 5 waypoints are possible) + X-coordinate of waypoint, set to NaN if not being used + Y-coordinate of waypoint, set to NaN if not being used + Z-coordinate of waypoint, set to NaN if not being used + X-velocity of waypoint, set to NaN if not being used + Y-velocity of waypoint, set to NaN if not being used + Z-velocity of waypoint, set to NaN if not being used + X-acceleration of waypoint, set to NaN if not being used + Y-acceleration of waypoint, set to NaN if not being used + Z-acceleration of waypoint, set to NaN if not being used + Yaw angle, set to NaN if not being used + Yaw rate, set to NaN if not being used + MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. + + + Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED). + 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. + Number of valid control points (up-to 5 points are possible) + X-coordinate of bezier control points. Set to NaN if not being used + Y-coordinate of bezier control points. Set to NaN if not being used + Z-coordinate of bezier control points. Set to NaN if not being used + Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated + Yaw. Set to NaN for unchanged + Status of the Iridium SBD link. 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. @@ -6656,4 +6683,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/csAirLink.xml b/ExtLibs/Mavlink/message_definitions/csAirLink.xml index 18b68eb998..43a377a030 100644 --- a/ExtLibs/Mavlink/message_definitions/csAirLink.xml +++ b/ExtLibs/Mavlink/message_definitions/csAirLink.xml @@ -27,4 +27,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/cubepilot.xml b/ExtLibs/Mavlink/message_definitions/cubepilot.xml index 4876287bd8..d08abbce7c 100644 --- a/ExtLibs/Mavlink/message_definitions/cubepilot.xml +++ b/ExtLibs/Mavlink/message_definitions/cubepilot.xml @@ -46,4 +46,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/development.xml b/ExtLibs/Mavlink/message_definitions/development.xml new file mode 100644 index 0000000000..2f037d9819 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/development.xml @@ -0,0 +1,348 @@ + + + + standard.xml + 0 + 0 + + + Airspeed sensor flags + + Airspeed sensor is unhealthy + + + True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. + + + + RADIO_RC_CHANNELS flags (bitmask). + + Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent. + + + Channel data may be out of date. This is set when the receiver is unable to validate incoming data from the transmitter and has therefore resent the last valid data it received. + + + + Standard modes with a well understood meaning across flight stacks and vehicle types. + For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. + Modes may be set using MAV_CMD_DO_SET_STANDARD_MODE. + + + Non standard mode. + This may be used when reporting the mode if the current flight mode is not a standard mode. + + + + Position mode (manual). + Position-controlled and stabilized manual mode. + When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. + This mode can only be set by vehicles that can hold a fixed position. + Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. + Hybrid MC/FW ("VTOL") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. + Fixed-wing (FW) vehicles must not support this mode. + Other vehicle types must not support this mode (this may be revisited through the PR process). + + + + Orbit (manual). + Position-controlled and stabilized manual mode. + The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. + Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. + Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters. + MC and FW vehicles may support this mode. + Hybrid MC/FW ("VTOL") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. + Other vehicle types must not support this mode (this may be revisited through the PR process). + + + + Cruise mode (manual). + Position-controlled and stabilized manual mode. + When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. + Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. + Hybrid MC/FW ("VTOL") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. + Multicopter (MC) vehicles must not support this mode. + Other vehicle types must not support this mode (this may be revisited through the PR process). + + + + Altitude hold (manual). + Altitude-controlled and stabilized manual mode. + When sticks are released vehicles return to their level-flight orientation and hold their altitude. + MC vehicles continue with existing momentum and may move with wind (or other external forces). + FW vehicles continue with current heading, but may be moved off-track by wind. + Hybrid MC/FW ("VTOL") vehicles behave according to their current configuration/mode (FW or MC). + Other vehicle types must not support this mode (this may be revisited through the PR process). + + + + Return home mode (auto). + Automatic mode that returns vehicle to home via a safe flight path. + It may also automatically land the vehicle (i.e. RTL). + The precise flight path and landing behaviour depend on vehicle configuration and type. + + + + Safe recovery mode (auto). + Automatic mode that takes vehicle to a predefined safe location via a safe flight path (rally point or mission defined landing) . + It may also automatically land the vehicle. + The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. + + + + Mission mode (automatic). + Automatic mode that executes MAVLink missions. + Missions are executed from the current waypoint as soon as the mode is enabled. + + + + Land mode (auto). + Automatic mode that lands the vehicle at the current location. + The precise landing behaviour depends on vehicle configuration and type. + + + + Takeoff mode (auto). + Automatic takeoff mode. + The precise takeoff behaviour depends on vehicle configuration and type. + + + + + Mode properties. + + + If set, this mode is an advanced mode. + For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. + A GCS can optionally use this flag to configure the UI for its intended users. + + + + If set, this mode should not be added to the list of selectable modes. + The mode might still be selected by the FC directly (for example as part of a failsafe). + + + + + + + + + + + Set system and component id. + This allows moving of a system and all its components to a new system id, or moving a particular component to a new system/component id. + Recipients must reject command addressed to broadcast system ID. + + New system ID for target component(s). 0: ignore and reject command (broadcast system ID not allowed). + New component ID for target component(s). 0: ignore (component IDs don't change). + Reboot components after ID change. Any non-zero value triggers the reboot. + + + + Set an external estimate of wind direction and speed. + This might be used to provide an initial wind estimate to the estimator (EKF) in the case where the vehicle is wind dead-reckoning, extending the time when operating without GPS before before position drift builds to an unsafe level. For this use case the command might reasonably be sent every few minutes when operating at altitude, and the value is cleared if the estimator resets itself. + + Horizontal wind speed. + Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown. + Azimuth (relative to true north) from where the wind is blowing. + Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown. + Empty + Empty + Empty + + + Enable the specified standard MAVLink mode. + If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED. + + The mode to set. + + + + + + + + + + Flags indicating errors in a GPS receiver. + + There are problems with incoming correction streams. + + + There are problems with the configuration. + + + There are problems with the software on the GPS receiver. + + + There are problems with an antenna connected to the GPS receiver. + + + There are problems handling all incoming events. + + + The GPS receiver CPU is overloaded. + + + The GPS receiver is experiencing output congestion. + + + + Signal authentication state in a GPS receiver. + + The GPS receiver does not provide GPS signal authentication info. + + + The GPS receiver is initializing signal authentication. + + + The GPS receiver encountered an error while initializing signal authentication. + + + The GPS receiver has correctly authenticated all signals. + + + GPS signal authentication is disabled on the receiver. + + + + Signal jamming state in a GPS receiver. + + The GPS receiver does not provide GPS signal jamming info. + + + The GPS receiver detected no signal jamming. + + + The GPS receiver detected and mitigated signal jamming. + + + The GPS receiver detected signal jamming. + + + + Signal spoofing state in a GPS receiver. + + The GPS receiver does not provide GPS signal spoofing info. + + + The GPS receiver detected no signal spoofing. + + + The GPS receiver detected and mitigated signal spoofing. + + + The GPS receiver detected signal spoofing but still has a fix. + + + + State of RAIM processing. + + RAIM capability is unknown. + + + RAIM is disabled. + + + RAIM integrity check was successful. + + + RAIM integrity check failed. + + + + + + Checksum for the current mission, rally point or geofence plan, or for the "combined" plan (a GCS can use these checksums to determine if it has matching plans). + This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition + (immediately after the MISSION_ACK that completes the upload sequence). + It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required. + The checksum must be calculated on the autopilot, but may also be calculated by the GCS. + The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation). + The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order): + frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7. + The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point. + + Mission type. + CRC32 checksum of current plan for specified type. + + + Airspeed information from a sensor. + Sensor ID. + Calibrated airspeed (CAS). + Temperature. INT16_MAX for value unknown/not supplied. + Raw differential pressure. NaN for value unknown/not supplied. + Airspeed sensor flags. + + + RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components (allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS). + Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar messages reported by the flight controller. + The target_system field should normally be set to the system id of the system to control, typically the flight controller. + The target_component field can normally be set to 0, so that all components of the system can receive the message. + The channels array field can publish up to 32 channels; the number of channel items used in the array is specified in the count field. + The time_last_update_ms field contains the timestamp of the last received valid channels data in the receiver's time domain. + The count field indicates the first index of the channel array that is not used for channel data (this and later indexes are zero-filled). + The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be validated so the last valid data is resent). + The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition is met (implementation dependent, e.g., connection to the RC radio is lost). + In this case time_last_update_ms still contains the timestamp of the last valid channels data, but the content of the channels data is not defined by the protocol (it is up to the implementation of the receiver). + For instance, the channels data could contain failsafe values configured in the receiver; the default is to carry the last valid data. + Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload and subject to MAVLink's trailing-zero trimming. + + System ID (ID of target system, normally flight controller). + Component ID (normally 0 for broadcast). + Time when the data in the channels field were last updated (time since boot in the receiver's time domain). + Radio RC channels status flags. + Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message. + + RC channels. + Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500. + Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming. + + + Get information about a particular flight modes. + The message can be enumerated or requested for a particular mode using MAV_CMD_REQUEST_MESSAGE. + Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. + The modes must be available/settable for the current vehicle/frame type. + Each modes should only be emitted once (even if it is both standard and custom). + + The total number of available modes for the current vehicle type. + The current mode index within number_modes, indexed from 1. + Standard mode. + A bitfield for use for autopilot-specific flags + Mode properties. + Name of custom mode, with null termination character. Should be omitted for standard modes. + + + Get the current mode. + This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). + It may be requested using MAV_CMD_REQUEST_MESSAGE. + + Standard mode. + A bitfield for use for autopilot-specific flags + The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied + + + A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. + A receiver must re-request all available modes whenever the sequence number changes. + This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. + + Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically). + + + Information about key components of GNSS receivers, like signal authentication, interference and system errors. + GNSS receiver id. Must match instance ids of other messages from same receiver. + Errors in the GPS system. + Signal authentication state of the GPS system. + Signal jamming state of the GPS system. + Signal spoofing state of the GPS system. + The state of the RAIM processing. + Horizontal expected accuracy using satellites successfully validated using RAIM. + Vertical expected accuracy using satellites successfully validated using RAIM. + An abstract value representing the estimated quality of incoming corrections, or 255 if not available. + An abstract value representing the overall status of the receiver, or 255 if not available. + An abstract value representing the quality of incoming GNSS signals, or 255 if not available. + An abstract value representing the estimated PPK quality, or 255 if not available. + + + diff --git a/ExtLibs/Mavlink/message_definitions/icarous.xml b/ExtLibs/Mavlink/message_definitions/icarous.xml index 9d2a2f6655..28aac2d2b4 100644 --- a/ExtLibs/Mavlink/message_definitions/icarous.xml +++ b/ExtLibs/Mavlink/message_definitions/icarous.xml @@ -46,4 +46,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/loweheiser.xml b/ExtLibs/Mavlink/message_definitions/loweheiser.xml index 8d8528b327..be3dc5aa49 100644 --- a/ExtLibs/Mavlink/message_definitions/loweheiser.xml +++ b/ExtLibs/Mavlink/message_definitions/loweheiser.xml @@ -53,4 +53,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/matrixpilot.xml b/ExtLibs/Mavlink/message_definitions/matrixpilot.xml new file mode 100644 index 0000000000..e3c4996c6f --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/matrixpilot.xml @@ -0,0 +1,349 @@ + + + common.xml + + + + Action required when performing CMD_PREFLIGHT_STORAGE + + Read all parameters from storage + + + Write all parameters to storage + + + Clear all parameters in storage + + + Read specific parameters from storage + + + Write specific parameters to storage + + + Clear specific parameters in storage + + + do nothing + + + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED + Storage area as defined by parameter database + Storage flags as defined by parameter database + Empty + Empty + Empty + Empty + + + + + + Depreciated but used as a compiler flag. Do not remove + System ID + Component ID + + + Reqest reading of flexifunction data + System ID + Component ID + Type of flexifunction data requested + index into data where needed + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + Total count of functions + Address in the flexifunction data, Set to 0xFFFF to use address in target memory + Size of the + Settings data + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + Settings data + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + Flexifunction command type + + + Acknowldge sucess or failure of a flexifunction command + Command acknowledged + result of acknowledge + + + Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A + Serial UDB Extra Time + Serial UDB Extra Status + Serial UDB Extra Latitude + Serial UDB Extra Longitude + Serial UDB Extra Altitude + Serial UDB Extra Waypoint Index + Serial UDB Extra Rmat 0 + Serial UDB Extra Rmat 1 + Serial UDB Extra Rmat 2 + Serial UDB Extra Rmat 3 + Serial UDB Extra Rmat 4 + Serial UDB Extra Rmat 5 + Serial UDB Extra Rmat 6 + Serial UDB Extra Rmat 7 + Serial UDB Extra Rmat 8 + Serial UDB Extra GPS Course Over Ground + Serial UDB Extra Speed Over Ground + Serial UDB Extra CPU Load + Serial UDB Extra 3D IMU Air Speed + Serial UDB Extra Estimated Wind 0 + Serial UDB Extra Estimated Wind 1 + Serial UDB Extra Estimated Wind 2 + Serial UDB Extra Magnetic Field Earth 0 + Serial UDB Extra Magnetic Field Earth 1 + Serial UDB Extra Magnetic Field Earth 2 + Serial UDB Extra Number of Sattelites in View + Serial UDB Extra GPS Horizontal Dilution of Precision + + + Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B + Serial UDB Extra Time + Serial UDB Extra PWM Input Channel 1 + Serial UDB Extra PWM Input Channel 2 + Serial UDB Extra PWM Input Channel 3 + Serial UDB Extra PWM Input Channel 4 + Serial UDB Extra PWM Input Channel 5 + Serial UDB Extra PWM Input Channel 6 + Serial UDB Extra PWM Input Channel 7 + Serial UDB Extra PWM Input Channel 8 + Serial UDB Extra PWM Input Channel 9 + Serial UDB Extra PWM Input Channel 10 + Serial UDB Extra PWM Input Channel 11 + Serial UDB Extra PWM Input Channel 12 + Serial UDB Extra PWM Output Channel 1 + Serial UDB Extra PWM Output Channel 2 + Serial UDB Extra PWM Output Channel 3 + Serial UDB Extra PWM Output Channel 4 + Serial UDB Extra PWM Output Channel 5 + Serial UDB Extra PWM Output Channel 6 + Serial UDB Extra PWM Output Channel 7 + Serial UDB Extra PWM Output Channel 8 + Serial UDB Extra PWM Output Channel 9 + Serial UDB Extra PWM Output Channel 10 + Serial UDB Extra PWM Output Channel 11 + Serial UDB Extra PWM Output Channel 12 + Serial UDB Extra IMU Location X + Serial UDB Extra IMU Location Y + Serial UDB Extra IMU Location Z + Serial UDB Location Error Earth X + Serial UDB Location Error Earth Y + Serial UDB Location Error Earth Z + Serial UDB Extra Status Flags + Serial UDB Extra Oscillator Failure Count + Serial UDB Extra IMU Velocity X + Serial UDB Extra IMU Velocity Y + Serial UDB Extra IMU Velocity Z + Serial UDB Extra Current Waypoint Goal X + Serial UDB Extra Current Waypoint Goal Y + Serial UDB Extra Current Waypoint Goal Z + Aeroforce in UDB X Axis + Aeroforce in UDB Y Axis + Aeroforce in UDB Z axis + SUE barometer temperature + SUE barometer pressure + SUE barometer altitude + SUE battery voltage + SUE battery current + SUE battery milli amp hours used + Sue autopilot desired height + Serial UDB Extra Stack Memory Free + + + Backwards compatible version of SERIAL_UDB_EXTRA F4: format + Serial UDB Extra Roll Stabilization with Ailerons Enabled + Serial UDB Extra Roll Stabilization with Rudder Enabled + Serial UDB Extra Pitch Stabilization Enabled + Serial UDB Extra Yaw Stabilization using Rudder Enabled + Serial UDB Extra Yaw Stabilization using Ailerons Enabled + Serial UDB Extra Navigation with Ailerons Enabled + Serial UDB Extra Navigation with Rudder Enabled + Serial UDB Extra Type of Alitude Hold when in Stabilized Mode + Serial UDB Extra Type of Alitude Hold when in Waypoint Mode + Serial UDB Extra Firmware racing mode enabled + + + Backwards compatible version of SERIAL_UDB_EXTRA F5: format + Serial UDB YAWKP_AILERON Gain for Proporional control of navigation + Serial UDB YAWKD_AILERON Gain for Rate control of navigation + Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization + + + Backwards compatible version of SERIAL_UDB_EXTRA F6: format + Serial UDB Extra PITCHGAIN Proportional Control + Serial UDB Extra Pitch Rate Control + Serial UDB Extra Rudder to Elevator Mix + Serial UDB Extra Roll to Elevator Mix + Gain For Boosting Manual Elevator control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F7: format + Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation + Serial UDB YAWKD_RUDDER Gain for Rate control of navigation + Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization + SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized + Serial UDB Extra Return To Landing - Angle to Pitch Plane Down + + + Backwards compatible version of SERIAL_UDB_EXTRA F8: format + Serial UDB Extra HEIGHT_TARGET_MAX + Serial UDB Extra HEIGHT_TARGET_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MAX + Serial UDB Extra ALT_HOLD_PITCH_MIN + Serial UDB Extra ALT_HOLD_PITCH_MAX + Serial UDB Extra ALT_HOLD_PITCH_HIGH + + + Backwards compatible version of SERIAL_UDB_EXTRA F13: format + Serial UDB Extra GPS Week Number + Serial UDB Extra MP Origin Latitude + Serial UDB Extra MP Origin Longitude + Serial UDB Extra MP Origin Altitude Above Sea Level + + + Backwards compatible version of SERIAL_UDB_EXTRA F14: format + Serial UDB Extra Wind Estimation Enabled + Serial UDB Extra Type of GPS Unit + Serial UDB Extra Dead Reckoning Enabled + Serial UDB Extra Type of UDB Hardware + Serial UDB Extra Type of Airframe + Serial UDB Extra Reboot Register of DSPIC + Serial UDB Extra Last dspic Trap Flags + Serial UDB Extra Type Program Address of Last Trap + Serial UDB Extra Number of Ocillator Failures + Serial UDB Extra UDB Internal Clock Configuration + Serial UDB Extra Type of Flight Plan + + + Backwards compatible version of SERIAL_UDB_EXTRA F15 format + Serial UDB Extra Model Name Of Vehicle + Serial UDB Extra Registraton Number of Vehicle + + + Backwards compatible version of SERIAL_UDB_EXTRA F16 format + Serial UDB Extra Name of Expected Lead Pilot + Serial UDB Extra URL of Lead Pilot or Team + + + The altitude measured by sensors and IMU + Timestamp (milliseconds since system boot) + GPS altitude (MSL) in meters, expressed as * 1000 (millimeters) + IMU altitude above ground in meters, expressed as * 1000 (millimeters) + barometeric altitude above ground in meters, expressed as * 1000 (millimeters) + Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) + Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) + Extra altitude above ground in meters, expressed as * 1000 (millimeters) + + + The airspeed measured by sensors and IMU + Timestamp (milliseconds since system boot) + Airspeed estimate from IMU, cm/s + Pitot measured forward airpseed, cm/s + Hot wire anenometer measured airspeed, cm/s + Ultrasonic measured airspeed, cm/s + Angle of attack sensor, degrees * 10 + Yaw angle sensor, degrees * 10 + + + Backwards compatible version of SERIAL_UDB_EXTRA F17 format + SUE Feed Forward Gain + SUE Max Turn Rate when Navigating + SUE Max Turn Rate in Fly By Wire Mode + + + Backwards compatible version of SERIAL_UDB_EXTRA F18 format + SUE Angle of Attack Normal + SUE Angle of Attack Inverted + SUE Elevator Trim Normal + SUE Elevator Trim Inverted + SUE reference_speed + + + Backwards compatible version of SERIAL_UDB_EXTRA F19 format + SUE aileron output channel + SUE aileron reversed + SUE elevator output channel + SUE elevator reversed + SUE throttle output channel + SUE throttle reversed + SUE rudder output channel + SUE rudder reversed + + + Backwards compatible version of SERIAL_UDB_EXTRA F20 format + SUE Number of Input Channels + SUE UDB PWM Trim Value on Input 1 + SUE UDB PWM Trim Value on Input 2 + SUE UDB PWM Trim Value on Input 3 + SUE UDB PWM Trim Value on Input 4 + SUE UDB PWM Trim Value on Input 5 + SUE UDB PWM Trim Value on Input 6 + SUE UDB PWM Trim Value on Input 7 + SUE UDB PWM Trim Value on Input 8 + SUE UDB PWM Trim Value on Input 9 + SUE UDB PWM Trim Value on Input 10 + SUE UDB PWM Trim Value on Input 11 + SUE UDB PWM Trim Value on Input 12 + + + Backwards compatible version of SERIAL_UDB_EXTRA F21 format + SUE X accelerometer offset + SUE Y accelerometer offset + SUE Z accelerometer offset + SUE X gyro offset + SUE Y gyro offset + SUE Z gyro offset + + + Backwards compatible version of SERIAL_UDB_EXTRA F22 format + SUE X accelerometer at calibration time + SUE Y accelerometer at calibration time + SUE Z accelerometer at calibration time + SUE X gyro at calibration time + SUE Y gyro at calibration time + SUE Z gyro at calibration time + + + diff --git a/ExtLibs/Mavlink/message_definitions/minimal.xml b/ExtLibs/Mavlink/message_definitions/minimal.xml index 8022e7ca94..5826587699 100644 --- a/ExtLibs/Mavlink/message_definitions/minimal.xml +++ b/ExtLibs/Mavlink/message_definitions/minimal.xml @@ -707,4 +707,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/offspec.xml b/ExtLibs/Mavlink/message_definitions/offspec.xml index c58f92a9a8..4364d004a3 100644 --- a/ExtLibs/Mavlink/message_definitions/offspec.xml +++ b/ExtLibs/Mavlink/message_definitions/offspec.xml @@ -4,7 +4,7 @@ 0 - + Information about video stream diff --git a/ExtLibs/Mavlink/message_definitions/paparazzi.xml b/ExtLibs/Mavlink/message_definitions/paparazzi.xml new file mode 100644 index 0000000000..45c9ec5542 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/paparazzi.xml @@ -0,0 +1,38 @@ + + + common.xml + 3 + + + + + + Message encoding a mission script item. This message is emitted upon a request for the next script item. + System ID + Component ID + Sequence + The name of the mission script, NULL terminated. + + + Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. + System ID + Component ID + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. + System ID + Component ID + Number of script items in the sequence + + + This message informs about the currently active SCRIPT. + Active Sequence + + + diff --git a/ExtLibs/Mavlink/message_definitions/python_array_test.xml b/ExtLibs/Mavlink/message_definitions/python_array_test.xml new file mode 100644 index 0000000000..7e4b72e146 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/python_array_test.xml @@ -0,0 +1,67 @@ + + + + common.xml + + + Array test #0. + Stub field + Value array + Value array + Value array + Value array + + + Array test #1. + Value array + + + Array test #3. + Stub field + Value array + + + Array test #4. + Value array + Stub field + + + Array test #5. + Value array + Value array + + + Array test #6. + Stub field + Stub field + Stub field + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #7. + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #8. + Stub field + Value array + Value array + + + diff --git a/ExtLibs/Mavlink/message_definitions/standard.xml b/ExtLibs/Mavlink/message_definitions/standard.xml new file mode 100644 index 0000000000..4ca39607ad --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/standard.xml @@ -0,0 +1,10 @@ + + + + common.xml + 0 + + + + + diff --git a/ExtLibs/Mavlink/message_definitions/storm32.xml b/ExtLibs/Mavlink/message_definitions/storm32.xml new file mode 100644 index 0000000000..7eada94e17 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/storm32.xml @@ -0,0 +1,571 @@ + + + + + ardupilotmega.xml + 1 + 0 + + + + + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + Registered for STorM32 gimbal controller. + + + + + + STorM32 gimbal prearm check flags. + + STorM32 gimbal is in normal state. + + + The IMUs are healthy and working normally. + + + The motors are active and working normally. + + + The encoders are healthy and working normally. + + + A battery voltage is applied and is in range. + + + ???. + + + Mavlink messages are being received. + + + The STorM32Link data indicates QFix. + + + The STorM32Link is working. + + + The camera has been found and is connected. + + + The signal on the AUX0 input pin is low. + + + The signal on the AUX1 input pin is low. + + + The NTLogger is working normally. + + + + + STorM32 camera prearm check flags. + + The camera has been found and is connected. + + + + + + Gimbal device capability flags. + + Gimbal device supports a retracted position. + + + Gimbal device supports a horizontal, forward looking position, stabilized. Can also be used to reset the gimbal's orientation. + + + Gimbal device supports rotating around roll axis. + + + 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). + + + Gimbal device supports rotating around pitch axis. + + + 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). + + + 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 locking to a heading angle. + + + Gimbal device supports yawing/panning infinitely (e.g. using a slip ring). + + + Gimbal device supports absolute yaw angles (this usually requires support by an autopilot, and can be dynamic, i.e., go on and off during runtime). + + + Gimbal device supports control via an RC input signal. + + + + + Flags for gimbal device operation. Used for setting and reporting, unless specified otherwise. Settings which are in violation of the capability flags are ignored by the gimbal device. + + Retracted safe position (no stabilization), takes presedence over NEUTRAL flag. If supported by the gimbal, the angles in the retracted position can be set in addition. + + + Neutral position (horizontal, forward looking, with stabiliziation). + + + Lock roll 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 drone). This is generally the default. + + + Lock yaw angle to absolute angle relative to earth (not relative to drone). When the YAW_ABSOLUTE flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). + + + Gimbal device can accept absolute yaw angle input. This flag cannot be set, is only for reporting (attempts to set it are rejected by the gimbal device). + + + Yaw angle is absolute (is only accepted if CAN_ACCEPT_YAW_ABSOLUTE is set). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). + + + RC control. The RC input signal fed to the gimbal device exclusively controls the gimbal's orientation. Overrides RC_MIXED flag if that is also set. + + + RC control. The RC input signal fed to the gimbal device is mixed into the gimbal's orientation. Is overriden by RC_EXCLUSIVE flag if that is also set. + + + UINT16_MAX = ignore. + + + + + Gimbal device error and condition flags (0 means no error or other condition). + + Gimbal device is limited by hardware roll limit. + + + Gimbal device is limited by hardware pitch limit. + + + Gimbal device is limited by hardware yaw limit. + + + There is an error with the gimbal device's encoders. + + + There is an error with the gimbal device's power source. + + + There is an error with the gimbal device's motors. + + + There is an error with the gimbal device's software. + + + There is an error with the gimbal device's communication. + + + Gimbal device is currently calibrating (not an error). + + + Gimbal device is not assigned to a gimbal manager (not an error). + + + + + + Gimbal manager capability flags. + + The gimbal manager supports several profiles. + + + The gimbal manager supports changing the gimbal manager during run time, i.e. can be enabled/disabled. + + + + + Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting is accepted by the gimbal manger, is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + + 0 = ignore. + + + Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive. + + + Request to set onboard/companion computer client to active, or report this client is active. + + + Request to set autopliot client to active, or report this client is active. + + + Request to set GCS client to active, or report this client is active. + + + Request to set camera client to active, or report this client is active. + + + Request to set GCS2 client to active, or report this client is active. + + + Request to set camera2 client to active, or report this client is active. + + + Request to set custom client to active, or report this client is active. + + + Request to set custom2 client to active, or report this client is active. + + + Request supervision. This flag is only for setting, it is not reported. + + + Release supervision. This flag is only for setting, it is not reported. + + + + + Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2. + + For convenience. + + + This is the onboard/companion computer client. + + + This is the autopilot client. + + + This is the GCS client. + + + This is the camera client. + + + This is the GCS2 client. + + + This is the camera2 client. + + + This is the custom client. + + + This is the custom2 client. + + + + + Flags for gimbal manager set up. Used for setting and reporting, unless specified otherwise. + + Enable gimbal manager. This flag is only for setting, is not reported. + + + Disable gimbal manager. This flag is only for setting, is not reported. + + + + + Gimbal manager profiles. Only standard profiles are defined. Any implementation can define it's own profile in addition, and should use enum values > 16. + + Default profile. Implementation specific. + + + Custom profile. Configurable profile according to the STorM32 definition. Is configured with STORM32_GIMBAL_MANAGER_PROFIL. + + + Default cooperative profile. Uses STorM32 custom profile with default settings to achieve cooperative behavior. + + + Default exclusive profile. Uses STorM32 custom profile with default settings to achieve exclusive behavior. + + + Default priority profile with cooperative behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior. + + + Default priority profile with exclusive behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior. + + + + + Gimbal actions. + + Trigger the gimbal device to recenter the gimbal. + + + Trigger the gimbal device to run a calibration. + + + Trigger gimbal device to (re)discover the gimbal manager during run time. + + + + + + Enumeration of possible shot modes. + + Undefined shot mode. Can be used to determine if qshots should be used or not. + + + Start normal gimbal operation. Is usally used to return back from a shot. + + + Load and keep safe gimbal position and stop stabilization. + + + Load neutral gimbal position and keep it while stabilizing. + + + Start mission with gimbal control. + + + Start RC gimbal control. + + + Start gimbal tracking the point specified by Lat, Lon, Alt. + + + Start gimbal tracking the system with specified system ID. + + + Start 2-point cable cam quick shot. + + + Start gimbal tracking the home location. + + + + + + + + + Command to a gimbal manager to control the gimbal tilt and pan angles. 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. A gimbal device is never to react to this command. + Pitch/tilt angle (positive: tilt up, NaN to be ignored). + Yaw/pan angle (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + Pitch/tilt rate (positive: tilt up, NaN to be ignored). + Yaw/pan rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + Gimbal device flags. + Gimbal manager flags. + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). The client is copied into bits 8-15. + + + + + Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + Gimbal manager profile (0 = default). + Gimbal manager setup flags (0 = none). + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. + + + + + Command to initiate gimbal actions. Usually performed by the gimbal device, but some can also be done by the gimbal manager. It is hence best to broadcast this command. + Gimbal action to initiate (0 = none). + Gimbal ID of the gimbal to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. + + + + + Command to set the shot manager mode. + Set shot mode. + Set shot state or command. The allowed values are specific to the selected shot mode. + + + + + + + + + + Message reporting the current status of a gimbal device. This message should be broadcasted by a gimbal device component at a low regular rate (e.g. 4 Hz). For higher rates it should be emitted with a target. + System ID + Component ID + Timestamp (time since system boot). + Gimbal device flags currently applied. + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag. + X component of angular velocity (NaN if unknown). + Y component of angular velocity (NaN if unknown). + Z component of angular velocity (the frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN if unknown). + Yaw in absolute frame relative to Earth's North, north is 0 (NaN if unknown). + Failure flags (0 for no failure). + + + + Message to a gimbal device to control its attitude. This message is to be sent from the gimbal manager to the gimbal device. Angles and rates can be set to NaN according to use case. + System ID + Component ID + Gimbal device flags (UINT16_MAX to be ignored). + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, set first element to NaN to be ignored). + X component of angular velocity (positive: roll to the right, NaN to be ignored). + Y component of angular velocity (positive: tilt up, NaN to be ignored). + Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + + + + + Information about a gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. It mirrors some fields of the STORM32_GIMBAL_DEVICE_INFORMATION message, but not all. If the additional information is desired, also STORM32_GIMBAL_DEVICE_INFORMATION should be requested. + Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. + Gimbal device capability flags. + Gimbal manager capability flags. + Hardware minimum roll angle (positive: roll to the right, NaN if unknown). + Hardware maximum roll angle (positive: roll to the right, NaN if unknown). + Hardware minimum pitch/tilt angle (positive: tilt up, NaN if unknown). + Hardware maximum pitch/tilt angle (positive: tilt up, NaN if unknown). + Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown). + Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown). + + + + Message reporting the current status of a gimbal manager. This message should be broadcast at a low regular rate (e.g. 1 Hz, may be increase momentarily to e.g. 5 Hz for a period of 1 sec after a change). + Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. + Client who is currently supervisor (0 = none). + Gimbal device flags currently applied. + Gimbal manager flags currently applied. + Profile currently applied (0 = default). + + + + Message to a gimbal manager to control the gimbal attitude. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Client which is contacting the gimbal manager (must be set). + Gimbal device flags (UINT16_MAX to be ignored). + Gimbal manager flags (0 to be ignored). + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the GIMBAL_MANAGER_FLAGS_ABSOLUTE_YAW flag, set first element to NaN to be ignored). + X component of angular velocity (positive: roll to the right, NaN to be ignored). + Y component of angular velocity (positive: tilt up, NaN to be ignored). + Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + + + + Message to a gimbal manager to control the gimbal tilt and pan angles. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Client which is contacting the gimbal manager (must be set). + Gimbal device flags (UINT16_MAX to be ignored). + Gimbal manager flags (0 to be ignored). + Pitch/tilt angle (positive: tilt up, NaN to be ignored). + Yaw/pan angle (positive: pan the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + Pitch/tilt angular rate (positive: tilt up, NaN to be ignored). + Yaw/pan angular rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored). + + + + Message to a gimbal manager to correct the gimbal roll angle. This message is typically used to manually correct for a tilted horizon in operation. A gimbal device is never to react to this message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Client which is contacting the gimbal manager (must be set). + Roll angle (positive to roll to the right). + + + + + Message to set a gimbal manager profile. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. + System ID + Component ID + Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). + Profile to be applied (0 = default). + Priorities for custom profile. + Profile flags for custom profile (0 = default). + Rc timeouts for custom profile (0 = infinite, in uints of 100 ms). + Timeouts for custom profile (0 = infinite, in uints of 100 ms). + + + + + + Information about the shot operation. + Current shot mode. + Current state in the shot. States are specific to the selected shot mode. + + + + + Message reporting the status of the prearm checks. The flags are component specific. + System ID + Component ID + Currently enabled prearm checks. 0 means no checks are being performed, UINT32_MAX means not known. + Currently not passed prearm checks. 0 means all checks have been passed. + + + diff --git a/ExtLibs/Mavlink/message_definitions/test.xml b/ExtLibs/Mavlink/message_definitions/test.xml new file mode 100644 index 0000000000..c680207462 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/ExtLibs/Mavlink/message_definitions/uAvionix.xml b/ExtLibs/Mavlink/message_definitions/uAvionix.xml index 3e24492055..97dbee9579 100644 --- a/ExtLibs/Mavlink/message_definitions/uAvionix.xml +++ b/ExtLibs/Mavlink/message_definitions/uAvionix.xml @@ -208,4 +208,3 @@ - diff --git a/ExtLibs/Mavlink/message_definitions/ualberta.xml b/ExtLibs/Mavlink/message_definitions/ualberta.xml new file mode 100644 index 0000000000..e0a6214a56 --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/ualberta.xml @@ -0,0 +1,76 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + + Raw input pulse widts sent to output + + + Inputs are normalized using calibration, the converted back to raw pulse widths for output + + + dfsdfs + + + dfsfds + + + dfsdfsdfs + + + + Navigation filter mode + + + AHRS mode + + + INS/GPS initialization mode + + + INS/GPS mode + + + + Mode currently commanded by pilot + + sdf + + + dfs + + + Rotomotion mode + + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/ExtLibs/Mavlink/regenerate.bat b/ExtLibs/Mavlink/regenerate.bat index f73dc34132..fc8fca5715 100644 --- a/ExtLibs/Mavlink/regenerate.bat +++ b/ExtLibs/Mavlink/regenerate.bat @@ -2,9 +2,9 @@ set PATH=c:\python27;%PATH% rd /s /q "mavlink" -python -m pymavlink.tools.mavgen --lang=CS --wire-protocol=2.0 "message_definitions\ardupilotmega.xml" "message_definitions\offspec.xml" +python -m pymavlink.tools.mavgen --lang=CS --wire-protocol=2.0 "message_definitions\all.xml" "message_definitions\offspec.xml" -python -m pymavlink.tools.mavgen --lang=WLua --wire-protocol=2.0 "message_definitions\ardupilotmega.xml" "message_definitions\offspec.xml" +python -m pymavlink.tools.mavgen --lang=WLua --wire-protocol=2.0 "message_definitions\all.xml" "message_definitions\offspec.xml" copy /y "mavlink\mavlink.cs" "Mavlink.cs" diff --git a/ExtLibs/Mavlink/updatexmls.bat b/ExtLibs/Mavlink/updatexmls.bat index bafde026ac..bdd624ac67 100644 --- a/ExtLibs/Mavlink/updatexmls.bat +++ b/ExtLibs/Mavlink/updatexmls.bat @@ -1,18 +1,16 @@ -python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/ardupilotmega.xml').read().decode('utf-8') )" > message_definitions\ardupilotmega.xml -python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/common.xml').read().decode('utf-8') )" > message_definitions\common.xml +rem https://github.com/ArduPilot/mavlink/tree/master/message_definitions/v1.0/ -python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/minimal.xml').read().decode('utf-8') )" > message_definitions\minimal.xml +echo import urllib.request; > update.py +echo for i, v in enumerate(['ASLUAV.xml', 'AVSSUAS.xml', 'all.xml', 'ardupilotmega.xml', 'common.xml', 'csAirLink.xml', 'cubepilot.xml', 'development.xml', 'icarous.xml', 'loweheiser.xml', 'matrixpilot.xml', 'minimal.xml', 'python_array_test.xml', 'paparazzi.xml', 'standard.xml', 'storm32.xml', 'test.xml', 'uAvionix.xml', 'ualberta.xml']): >> update.py +echo print(v, "\n") +echo f = open("message_definitions/"+v, "w")>> update.py +echo f.write(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/'+v).read().decode('utf-8'))>> update.py +echo f.close()>> update.py -python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/uAvionix.xml').read().decode('utf-8') )" > message_definitions\uAvionix.xml +python update.py -python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/icarous.xml').read().decode('utf-8') )" > message_definitions\icarous.xml - -python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/loweheiser.xml').read().decode('utf-8') )" > message_definitions\loweheiser.xml - -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 +del update.py pause \ No newline at end of file diff --git a/ExtLibs/Utilities/ParameterMetaDataRepositoryAPMpdef.cs b/ExtLibs/Utilities/ParameterMetaDataRepositoryAPMpdef.cs index edffe4747a..b70a254cc8 100644 --- a/ExtLibs/Utilities/ParameterMetaDataRepositoryAPMpdef.cs +++ b/ExtLibs/Utilities/ParameterMetaDataRepositoryAPMpdef.cs @@ -23,11 +23,18 @@ public static class ParameterMetaDataRepositoryAPMpdef private static string[] vehicles = new[] { "SITL", "AP_Periph", "ArduSub", "Rover", "ArduCopter", - "ArduPlane", "AntennaTracker", "Blimp", "Heli" + "ArduPlane", "AntennaTracker", "Blimp", "Heli" + }; + + private static string[] vehicles_versioned = new[] + { + "Copter", "Plane", "Rover", "Sub", "Tracker" }; static string url = "https://autotest.ardupilot.org/Parameters/{0}/apm.pdef.xml.gz"; + static string urlversioned = "https://autotest.ardupilot.org/Parameters/versioned/{0}/stable-{1}/apm.pdef.xml"; + static ParameterMetaDataRepositoryAPMpdef() { GetMetaData(); @@ -42,6 +49,42 @@ public static void CheckLoad(string vehicle = "") Reload(vehicle); } + public static async Task GetMetaDataVersioned(Version version) + { + List tlist = new List(); + + vehicles_versioned.ForEach(a => + { + try + { + var newurl = String.Format(urlversioned, a, version.ToString()); + var file = Path.Combine(Settings.GetDataDirectory(), a + version.ToString() + ".apm.pdef.xml"); + if (File.Exists(file)) + if (new FileInfo(file).LastWriteTime.AddDays(7) > DateTime.Now) + return; + var dltask = Download.getFilefromNetAsync(newurl, file); + tlist.Add(dltask); + } + catch (Exception ex) { log.Error(ex); } + }); + + await Task.WhenAll(tlist); + + vehicles_versioned.ForEach(a => + { + try + { + Reload(a + version.ToString()); + + var veh = vehicles.First(b => b.Contains(a)); + + if(_parameterMetaDataXML.ContainsKey(a + version.ToString())) + _parameterMetaDataXML[veh] = _parameterMetaDataXML[a + version.ToString()]; + } + catch (Exception ex) { log.Error(ex); } + }); + } + public static async Task GetMetaData(bool force = false) { List tlist = new List(); diff --git a/ExtLibs/Utilities/SignedFW.cs b/ExtLibs/Utilities/SignedFW.cs index 75eb7079dd..ce04882082 100644 --- a/ExtLibs/Utilities/SignedFW.cs +++ b/ExtLibs/Utilities/SignedFW.cs @@ -8,6 +8,7 @@ using Org.BouncyCastle.Crypto.Digests; using Org.BouncyCastle.Crypto.Generators; using Org.BouncyCastle.Crypto.Parameters; +using Org.BouncyCastle.Crypto.Prng; using Org.BouncyCastle.Security; namespace MissionPlanner.Utilities @@ -29,6 +30,20 @@ public static AsymmetricCipherKeyPair GenerateKey() return keyPairg; } + public static AsymmetricCipherKeyPair GenerateKey(byte[] knownseed) + { + //Creating Random + var secureRandom = new SecureRandom(new preseedrandom(knownseed)); + + //Parameters creation using the random and keysize + var keyGenParam = new KeyGenerationParameters(secureRandom, 256); + + var generator = new Ed25519KeyPairGenerator(); + generator.Init(keyGenParam); + AsymmetricCipherKeyPair keyPairg = generator.GenerateKeyPair(); + return keyPairg; + } + public static byte[] CreateSignedBL(AsymmetricCipherKeyPair keyPair, string filename) { var descriptor = new byte[] { 0x4e, 0xcf, 0x4e, 0xa5, 0xa6, 0xb6, 0xf7, 0x29 }; @@ -124,5 +139,35 @@ public static byte[] CreateSignedAPJ(AsymmetricCipherKeyPair keyPair, string fil return System.Text.ASCIIEncoding.ASCII.GetBytes(JsonConvert.SerializeObject(d, Formatting.Indented)); } + + private class preseedrandom : IRandomGenerator + { + private byte[] knownseed; + + public preseedrandom(byte[] knownseed) + { + this.knownseed = knownseed; + } + + public void AddSeedMaterial(byte[] seed) + { + throw new NotImplementedException(); + } + + public void AddSeedMaterial(long seed) + { + throw new NotImplementedException(); + } + + public void NextBytes(byte[] bytes) + { + Array.Copy(knownseed, bytes, bytes.Length); + } + + public void NextBytes(byte[] bytes, int start, int len) + { + throw new NotImplementedException(); + } + } } } diff --git a/ExtLibs/Utilities/Spline2.cs b/ExtLibs/Utilities/Spline2.cs index 80316d4035..07f4ecec43 100644 --- a/ExtLibs/Utilities/Spline2.cs +++ b/ExtLibs/Utilities/Spline2.cs @@ -1,409 +1,409 @@ -using System; -using MissionPlanner.Utilities; -using uint32_t = System.UInt32; -using int32_t = System.Int32; - -namespace MissionPlanner.Controls.Waypoints -{ - public class Spline2 : Utils - { - public Vector3 target_pos = new Vector3(); - public Vector3 target_vel = new Vector3(); - - // spline segment end types enum - public enum spline_segment_end_type - { - SEGMENT_END_STOP = 0, - SEGMENT_END_STRAIGHT, - SEGMENT_END_SPLINE - }; - - // segment types, either straight or spine - public enum SegmentType - { - SEGMENT_STRAIGHT = 0, - SEGMENT_SPLINE = 1 - }; - - public struct wpnav_flags - { - public bool reached_destination; // true if we have reached the destination - - public bool fast_waypoint; - // true if we should ignore the waypoint radius and consider the waypoint complete once the intermediate target has reached the waypoint - - public SegmentType segment_type; // active segment is either straight or spline - }; - - public wpnav_flags _flags = new wpnav_flags(); - - // spline variables - float _spline_time = 0; // current spline time between origin and destination - - public Vector3 _spline_origin_vel = new Vector3(); - // the target velocity vector at the origin of the spline segment - - Vector3 _spline_destination_vel = new Vector3(); - // the target velocity vector at the destination point of the spline segment - - Vector3[] _hermite_spline_solution = new Vector3[4]; - // array describing spline path between origin and destination - - float _spline_vel_scaler = 0; // - float _slow_down_dist; // vehicle should begin to slow down once it is within this distance from the destination - // To-Do: this should be used for straight segments as well - float _yaw; // heading according to yaw - private float _wp_accel_cms = 100; // 1 m/s/s - private uint32_t _wp_last_update; - private float _wp_speed_cms = 600; // 6 m/s - public Vector3 _origin; - public Vector3 _destination; - private object _wp_speed_up_cms = 100; - //private int _wp_speed_down_cms = 100; - - double scaleLongDown; - double scaleLongUp; - - // pv_latlon_to_vector - convert lat/lon coordinates to a position vector - public Vector3 pv_location_to_vector(PointLatLngAlt loc) - { - PointLatLngAlt home = homeLocation; - - scaleLongDown = longitude_scale(home); - scaleLongUp = 1.0f/scaleLongDown; - - Vector3 tmp = new Vector3((loc.Lat*1.0e7f - home.Lat*1.0e7f)*LATLON_TO_CM, - (loc.Lng*1.0e7f - home.Lng*1.0e7f)*LATLON_TO_CM*scaleLongDown, loc.Alt*100); - return tmp; - } - - public PointLatLngAlt pv_vector_to_location(Vector3 loc) - { - return new PointLatLngAlt(pv_get_lat(loc)*1.0e-7f, pv_get_lon(loc)*1.0e-7f, loc.z/100, ""); - } - - // pv_get_lon - extract latitude from position vector - int32_t pv_get_lat(Vector3 pos_vec) - { - PointLatLngAlt home = homeLocation; - - return (int32_t) (home.Lat*1.0e7f) + (int32_t) (pos_vec.x/LATLON_TO_CM); - } - - // pv_get_lon - extract longitude from position vector - int32_t pv_get_lon(Vector3 pos_vec) - { - PointLatLngAlt home = homeLocation; - - return (int32_t) (home.Lng*1.0e7f) + (int32_t) (pos_vec.y/LATLON_TO_CM*scaleLongUp); - } - - const float LATLON_TO_CM = 1.113195f; - +using System; +using MissionPlanner.Utilities; +using uint32_t = System.UInt32; +using int32_t = System.Int32; + +namespace MissionPlanner.Controls.Waypoints +{ + public class Spline2 : Utils + { + public Vector3 target_pos = new Vector3(); + public Vector3 target_vel = new Vector3(); + + // spline segment end types enum + public enum spline_segment_end_type + { + SEGMENT_END_STOP = 0, + SEGMENT_END_STRAIGHT, + SEGMENT_END_SPLINE + }; + + // segment types, either straight or spine + public enum SegmentType + { + SEGMENT_STRAIGHT = 0, + SEGMENT_SPLINE = 1 + }; + + public struct wpnav_flags + { + public bool reached_destination; // true if we have reached the destination + + public bool fast_waypoint; + // true if we should ignore the waypoint radius and consider the waypoint complete once the intermediate target has reached the waypoint + + public SegmentType segment_type; // active segment is either straight or spline + }; + + public wpnav_flags _flags = new wpnav_flags(); + + // spline variables + float _spline_time = 0; // current spline time between origin and destination + + public Vector3 _spline_origin_vel = new Vector3(); + // the target velocity vector at the origin of the spline segment + + Vector3 _spline_destination_vel = new Vector3(); + // the target velocity vector at the destination point of the spline segment + + Vector3[] _hermite_spline_solution = new Vector3[4]; + // array describing spline path between origin and destination + + float _spline_vel_scaler = 0; // + float _slow_down_dist; // vehicle should begin to slow down once it is within this distance from the destination + // To-Do: this should be used for straight segments as well + float _yaw; // heading according to yaw + public static float _wp_accel_cms { get; set; } = 100; // 1 m/s/s + private uint32_t _wp_last_update; + public static float _wp_speed_cms { get; set; } = 600; // 6 m/s + public Vector3 _origin; + public Vector3 _destination; + private object _wp_speed_up_cms = 100; + //private int _wp_speed_down_cms = 100; + + double scaleLongDown; + double scaleLongUp; + + // pv_latlon_to_vector - convert lat/lon coordinates to a position vector + public Vector3 pv_location_to_vector(PointLatLngAlt loc) + { + PointLatLngAlt home = homeLocation; + + scaleLongDown = longitude_scale(home); + scaleLongUp = 1.0f/scaleLongDown; + + Vector3 tmp = new Vector3((loc.Lat*1.0e7f - home.Lat*1.0e7f)*LATLON_TO_CM, + (loc.Lng*1.0e7f - home.Lng*1.0e7f)*LATLON_TO_CM*scaleLongDown, loc.Alt*100); + return tmp; + } + + public PointLatLngAlt pv_vector_to_location(Vector3 loc) + { + return new PointLatLngAlt(pv_get_lat(loc)*1.0e-7f, pv_get_lon(loc)*1.0e-7f, loc.z/100, ""); + } + + // pv_get_lon - extract latitude from position vector + int32_t pv_get_lat(Vector3 pos_vec) + { + PointLatLngAlt home = homeLocation; + + return (int32_t) (home.Lat*1.0e7f) + (int32_t) (pos_vec.x/LATLON_TO_CM); + } + + // pv_get_lon - extract longitude from position vector + int32_t pv_get_lon(Vector3 pos_vec) + { + PointLatLngAlt home = homeLocation; + + return (int32_t) (home.Lng*1.0e7f) + (int32_t) (pos_vec.y/LATLON_TO_CM*scaleLongUp); + } + + const float LATLON_TO_CM = 1.113195f; + private PointLatLngAlt homeLocation; - public Spline2(PointLatLngAlt homeLocation) - { - this.homeLocation = homeLocation; + public Spline2(PointLatLngAlt homeLocation) + { + this.homeLocation = homeLocation; + } + + float longitude_scale(PointLatLngAlt loc) + { + float scale = 1.0f; + scale = (float) Math.Cos(loc.Lat*MathHelper.deg2rad); + return scale; + } + + private void calculate_wp_leash_length() + { + //throw new NotImplementedException(); + } + + /// set_origin_and_destination - set origin and destination using lat/lon coordinates + public void set_wp_origin_and_destination(Vector3 origin, Vector3 destination) + { + // store origin and destination locations + _origin = origin; + _destination = destination; + Vector3 pos_delta = _destination - _origin; + + _track_length = pos_delta.length(); // get track length + + _flags.reached_destination = false; + _flags.fast_waypoint = false; // default waypoint back to slow + _flags.segment_type = SegmentType.SEGMENT_STRAIGHT; + } + + /// set_spline_destination waypoint using position vector (distance from home in cm) + /// seg_type should be calculated by calling function based on the mission + public void set_spline_destination(Vector3 destination, bool stopped_at_start, + spline_segment_end_type seg_end_type, Vector3 next_destination) + { + // should be origin + Vector3 origin; + + // if waypoint controller is active and copter has reached the previous waypoint use it for the origin + if (_flags.reached_destination) + { +// && ((hal.scheduler->millis() - _wp_last_update) < 1000) ) { + origin = _destination; + } + else + { + // my edit + origin = _origin; + // otherwise calculate origin from the current position and velocity + //_pos_control.get_stopping_point_xy(origin); + //_pos_control.get_stopping_point_z(origin); + } + + // set origin and destination + set_spline_origin_and_destination(origin, destination, stopped_at_start, seg_end_type, next_destination); + } + + /// set_spline_origin_and_destination - set origin and destination waypoints using position vectors (distance from home in cm) + /// seg_type should be calculated by calling function based on the mission + void set_spline_origin_and_destination(Vector3 origin, Vector3 destination, bool stopped_at_start, + spline_segment_end_type seg_end_type, Vector3 next_destination) + { + // mission is "active" if wpnav has been called recently and vehicle reached the previous waypoint + bool prev_segment_exists = (_flags.reached_destination); + // && ((hal.scheduler->millis() - _wp_last_update) < 1000)); + + // segment start types + // stop - vehicle is not moving at origin + // straight-fast - vehicle is moving, previous segment is straight. vehicle will fly straight through the waypoint before beginning it's spline path to the next wp + // _flag.segment_type holds whether prev segment is straight vs spline but we don't know if it has a delay + // spline-fast - vehicle is moving, previous segment is splined, vehicle will fly through waypoint but previous segment should have it flying in the correct direction (i.e. exactly parallel to position difference vector from previous segment's origin to this segment's destination) + + // calculate spline velocity at origin + if (stopped_at_start || !prev_segment_exists) + { + // if vehicle is stopped at the origin, set origin velocity to 0.1 * distance vector from origin to destination + _spline_origin_vel = (destination - origin)*0.1f; + _spline_time = 0.0f; + _spline_vel_scaler = 0.0f; + } + else + { + // look at previous segment to determine velocity at origin + if (_flags.segment_type == SegmentType.SEGMENT_STRAIGHT) + { + // previous segment is straight, vehicle is moving so vehicle should fly straight through the origin + // before beginning it's spline path to the next waypoint. Note: we are using the previous segment's origin and destination + _spline_origin_vel = (_destination - _origin); + _spline_time = 0.0f; + // To-Do: this should be set based on how much overrun there was from straight segment? + _spline_vel_scaler = 0.0f; + // To-Do: this should be set based on speed at end of prev straight segment? + } + else + { + // previous segment is splined, vehicle will fly through origin + // we can use the previous segment's destination velocity as this segment's origin velocity + // Note: previous segment will leave destination velocity parallel to position difference vector + // from previous segment's origin to this segment's destination) + _spline_origin_vel = _spline_destination_vel; + if (_spline_time > 1.0f && _spline_time < 1.1f) + { + // To-Do: remove hard coded 1.1f + _spline_time -= 1.0f; + } + else + { + _spline_time = 0.0f; + } + _spline_vel_scaler = 0.0f; + } + } + + // calculate spline velocity at destination + switch (seg_end_type) + { + case spline_segment_end_type.SEGMENT_END_STOP: + // if vehicle stops at the destination set destination velocity to 0.1 * distance vector from origin to destination + _spline_destination_vel = (destination - origin)*0.1f; + _flags.fast_waypoint = false; + break; + + case spline_segment_end_type.SEGMENT_END_STRAIGHT: + // if next segment is straight, vehicle's final velocity should face along the next segment's position + _spline_destination_vel = (next_destination - destination); + _flags.fast_waypoint = true; + break; + + case spline_segment_end_type.SEGMENT_END_SPLINE: + // if next segment is splined, vehicle's final velocity should face parallel to the line from the origin to the next destination + _spline_destination_vel = (next_destination - origin); + _flags.fast_waypoint = true; + break; + } + + // code below ensures we don't get too much overshoot when the next segment is short + float vel_len = (float) ((_spline_origin_vel + _spline_destination_vel).length()); + float pos_len = (float) (destination - origin).length()*4.0f; + if (vel_len > pos_len) + { + // if total start+stop velocity is more than twice position difference + // use a scaled down start and stop velocityscale the start and stop velocities down + float vel_scaling = pos_len/vel_len; + // update spline calculator + update_spline_solution(origin, destination, _spline_origin_vel*vel_scaling, + _spline_destination_vel*vel_scaling); + } + else + { + // update spline calculator + update_spline_solution(origin, destination, _spline_origin_vel, _spline_destination_vel); + } + + // initialise yaw heading to current heading + //_yaw = _ahrs->yaw_sensor; + + // store origin and destination locations + _origin = origin; + _destination = destination; + + // calculate slow down distance + calc_slow_down_distance(_wp_speed_cms, _wp_accel_cms); + + // initialise intermediate point to the origin + //_pos_control.set_pos_target(origin); + _flags.reached_destination = false; + _flags.segment_type = SegmentType.SEGMENT_SPLINE; + } + + /// calc_slow_down_distance - calculates distance before waypoint that target point should begin to slow-down assuming it is travelling at full speed + void calc_slow_down_distance(float speed_cms, float accel_cmss) + { + // protect against divide by zero + if (accel_cmss <= 0.0f) + { + _slow_down_dist = 0.0f; + return; + } + // To-Do: should we use a combination of horizontal and vertical speeds? + // To-Do: update this automatically when speed or acceleration is changed + _slow_down_dist = speed_cms*speed_cms/(4.0f*accel_cmss); + } + + + /// update_spline - update spline controller + public void update_spline() + { + // exit immediately if this is not a spline segment + if (_flags.segment_type != SegmentType.SEGMENT_SPLINE) + { + return; + } + + // calculate dt + uint32_t now = 0; //hal.scheduler->millis(); + float dt = (now - _wp_last_update)/1000.0f; + + // reset step back to 0 if 0.1 seconds has passed and we completed the last full cycle + if (dt > 0.095f) + { + // double check dt is reasonable + if (dt >= 1.0f) + { + dt = 0.0f; + } + // capture time since last iteration + _wp_last_update = now; + + // advance the target if necessary + advance_spline_target_along_track(dt); + //_pos_control.trigger_xy(); + } + else + { + // run position controller + //_pos_control.update_pos_controller(false); + } + } + + void update_spline_solution(Vector3 origin, Vector3 dest, Vector3 origin_vel, Vector3 dest_vel) + { + _hermite_spline_solution[0] = origin; + _hermite_spline_solution[1] = origin_vel; + _hermite_spline_solution[2] = -origin*3.0f - origin_vel*2.0f + dest*3.0f - dest_vel; + _hermite_spline_solution[3] = origin*2.0f + origin_vel - dest*2.0f + dest_vel; + } + + public void advance_spline_target_along_track(float dt) + { + if (!_flags.reached_destination) + { + // update target position and velocity from spline calculator + calc_spline_pos_vel(_spline_time, ref target_pos, ref target_vel); + + // update velocity + float spline_dist_to_wp = (float) (_destination - target_pos).length(); + + // if within the stopping distance from destination, set target velocity to sqrt of distance * 2 * acceleration + if (!_flags.fast_waypoint && spline_dist_to_wp < _slow_down_dist) + { + _spline_vel_scaler = (float) Math.Sqrt(spline_dist_to_wp*2.0f*_wp_accel_cms); + } + else if (_spline_vel_scaler < _wp_speed_cms) + { + // increase velocity using acceleration + // To-Do: replace 0.1f below with update frequency passed in from main program + _spline_vel_scaler += _wp_accel_cms*dt; + } + + // constrain target velocity + if (_spline_vel_scaler > _wp_speed_cms) + { + _spline_vel_scaler = _wp_speed_cms; + } + + // scale the spline_time by the velocity we've calculated vs the velocity that came out of the spline calculator + float spline_time_scale = (float) (_spline_vel_scaler/target_vel.length()); + + // update target position + //_pos_control.set_pos_target(target_pos); + + // update the yaw + _yaw = RadiansToCentiDegrees(atan2(target_vel.y, target_vel.x)); + + // advance spline time to next step + _spline_time += spline_time_scale*dt; + + // 20 segments per spline + // _spline_time +=0.05f; + + // we will reach the next waypoint in the next step so set reached_destination flag + // To-Do: is this one step too early? + if (_spline_time >= 1.0f) + { + _flags.reached_destination = true; + } + } + } + + private float RadiansToCentiDegrees(double p) + { + return (float) (p*MathHelper.rad2deg); + } + + + void calc_spline_pos_vel(float spline_time, ref Vector3 position, ref Vector3 velocity) + { + float spline_time_sqrd = spline_time*spline_time; + float spline_time_cubed = spline_time_sqrd*spline_time; + + position = _hermite_spline_solution[0] + + _hermite_spline_solution[1]*spline_time + + _hermite_spline_solution[2]*spline_time_sqrd + + _hermite_spline_solution[3]*spline_time_cubed; + + velocity = _hermite_spline_solution[1] + + _hermite_spline_solution[2]*2.0f*spline_time + + _hermite_spline_solution[3]*3.0f*spline_time_sqrd; } - float longitude_scale(PointLatLngAlt loc) - { - float scale = 1.0f; - scale = (float) Math.Cos(loc.Lat*MathHelper.deg2rad); - return scale; - } - - private void calculate_wp_leash_length() - { - //throw new NotImplementedException(); - } - - /// set_origin_and_destination - set origin and destination using lat/lon coordinates - public void set_wp_origin_and_destination(Vector3 origin, Vector3 destination) - { - // store origin and destination locations - _origin = origin; - _destination = destination; - Vector3 pos_delta = _destination - _origin; - - _track_length = pos_delta.length(); // get track length - - _flags.reached_destination = false; - _flags.fast_waypoint = false; // default waypoint back to slow - _flags.segment_type = SegmentType.SEGMENT_STRAIGHT; - } - - /// set_spline_destination waypoint using position vector (distance from home in cm) - /// seg_type should be calculated by calling function based on the mission - public void set_spline_destination(Vector3 destination, bool stopped_at_start, - spline_segment_end_type seg_end_type, Vector3 next_destination) - { - // should be origin - Vector3 origin; - - // if waypoint controller is active and copter has reached the previous waypoint use it for the origin - if (_flags.reached_destination) - { -// && ((hal.scheduler->millis() - _wp_last_update) < 1000) ) { - origin = _destination; - } - else - { - // my edit - origin = _origin; - // otherwise calculate origin from the current position and velocity - //_pos_control.get_stopping_point_xy(origin); - //_pos_control.get_stopping_point_z(origin); - } - - // set origin and destination - set_spline_origin_and_destination(origin, destination, stopped_at_start, seg_end_type, next_destination); - } - - /// set_spline_origin_and_destination - set origin and destination waypoints using position vectors (distance from home in cm) - /// seg_type should be calculated by calling function based on the mission - void set_spline_origin_and_destination(Vector3 origin, Vector3 destination, bool stopped_at_start, - spline_segment_end_type seg_end_type, Vector3 next_destination) - { - // mission is "active" if wpnav has been called recently and vehicle reached the previous waypoint - bool prev_segment_exists = (_flags.reached_destination); - // && ((hal.scheduler->millis() - _wp_last_update) < 1000)); - - // segment start types - // stop - vehicle is not moving at origin - // straight-fast - vehicle is moving, previous segment is straight. vehicle will fly straight through the waypoint before beginning it's spline path to the next wp - // _flag.segment_type holds whether prev segment is straight vs spline but we don't know if it has a delay - // spline-fast - vehicle is moving, previous segment is splined, vehicle will fly through waypoint but previous segment should have it flying in the correct direction (i.e. exactly parallel to position difference vector from previous segment's origin to this segment's destination) - - // calculate spline velocity at origin - if (stopped_at_start || !prev_segment_exists) - { - // if vehicle is stopped at the origin, set origin velocity to 0.1 * distance vector from origin to destination - _spline_origin_vel = (destination - origin)*0.1f; - _spline_time = 0.0f; - _spline_vel_scaler = 0.0f; - } - else - { - // look at previous segment to determine velocity at origin - if (_flags.segment_type == SegmentType.SEGMENT_STRAIGHT) - { - // previous segment is straight, vehicle is moving so vehicle should fly straight through the origin - // before beginning it's spline path to the next waypoint. Note: we are using the previous segment's origin and destination - _spline_origin_vel = (_destination - _origin); - _spline_time = 0.0f; - // To-Do: this should be set based on how much overrun there was from straight segment? - _spline_vel_scaler = 0.0f; - // To-Do: this should be set based on speed at end of prev straight segment? - } - else - { - // previous segment is splined, vehicle will fly through origin - // we can use the previous segment's destination velocity as this segment's origin velocity - // Note: previous segment will leave destination velocity parallel to position difference vector - // from previous segment's origin to this segment's destination) - _spline_origin_vel = _spline_destination_vel; - if (_spline_time > 1.0f && _spline_time < 1.1f) - { - // To-Do: remove hard coded 1.1f - _spline_time -= 1.0f; - } - else - { - _spline_time = 0.0f; - } - _spline_vel_scaler = 0.0f; - } - } - - // calculate spline velocity at destination - switch (seg_end_type) - { - case spline_segment_end_type.SEGMENT_END_STOP: - // if vehicle stops at the destination set destination velocity to 0.1 * distance vector from origin to destination - _spline_destination_vel = (destination - origin)*0.1f; - _flags.fast_waypoint = false; - break; - - case spline_segment_end_type.SEGMENT_END_STRAIGHT: - // if next segment is straight, vehicle's final velocity should face along the next segment's position - _spline_destination_vel = (next_destination - destination); - _flags.fast_waypoint = true; - break; - - case spline_segment_end_type.SEGMENT_END_SPLINE: - // if next segment is splined, vehicle's final velocity should face parallel to the line from the origin to the next destination - _spline_destination_vel = (next_destination - origin); - _flags.fast_waypoint = true; - break; - } - - // code below ensures we don't get too much overshoot when the next segment is short - float vel_len = (float) ((_spline_origin_vel + _spline_destination_vel).length()); - float pos_len = (float) (destination - origin).length()*4.0f; - if (vel_len > pos_len) - { - // if total start+stop velocity is more than twice position difference - // use a scaled down start and stop velocityscale the start and stop velocities down - float vel_scaling = pos_len/vel_len; - // update spline calculator - update_spline_solution(origin, destination, _spline_origin_vel*vel_scaling, - _spline_destination_vel*vel_scaling); - } - else - { - // update spline calculator - update_spline_solution(origin, destination, _spline_origin_vel, _spline_destination_vel); - } - - // initialise yaw heading to current heading - //_yaw = _ahrs->yaw_sensor; - - // store origin and destination locations - _origin = origin; - _destination = destination; - - // calculate slow down distance - calc_slow_down_distance(_wp_speed_cms, _wp_accel_cms); - - // initialise intermediate point to the origin - //_pos_control.set_pos_target(origin); - _flags.reached_destination = false; - _flags.segment_type = SegmentType.SEGMENT_SPLINE; - } - - /// calc_slow_down_distance - calculates distance before waypoint that target point should begin to slow-down assuming it is travelling at full speed - void calc_slow_down_distance(float speed_cms, float accel_cmss) - { - // protect against divide by zero - if (accel_cmss <= 0.0f) - { - _slow_down_dist = 0.0f; - return; - } - // To-Do: should we use a combination of horizontal and vertical speeds? - // To-Do: update this automatically when speed or acceleration is changed - _slow_down_dist = speed_cms*speed_cms/(4.0f*accel_cmss); - } - - - /// update_spline - update spline controller - public void update_spline() - { - // exit immediately if this is not a spline segment - if (_flags.segment_type != SegmentType.SEGMENT_SPLINE) - { - return; - } - - // calculate dt - uint32_t now = 0; //hal.scheduler->millis(); - float dt = (now - _wp_last_update)/1000.0f; - - // reset step back to 0 if 0.1 seconds has passed and we completed the last full cycle - if (dt > 0.095f) - { - // double check dt is reasonable - if (dt >= 1.0f) - { - dt = 0.0f; - } - // capture time since last iteration - _wp_last_update = now; - - // advance the target if necessary - advance_spline_target_along_track(dt); - //_pos_control.trigger_xy(); - } - else - { - // run position controller - //_pos_control.update_pos_controller(false); - } - } - - void update_spline_solution(Vector3 origin, Vector3 dest, Vector3 origin_vel, Vector3 dest_vel) - { - _hermite_spline_solution[0] = origin; - _hermite_spline_solution[1] = origin_vel; - _hermite_spline_solution[2] = -origin*3.0f - origin_vel*2.0f + dest*3.0f - dest_vel; - _hermite_spline_solution[3] = origin*2.0f + origin_vel - dest*2.0f + dest_vel; - } - - public void advance_spline_target_along_track(float dt) - { - if (!_flags.reached_destination) - { - // update target position and velocity from spline calculator - calc_spline_pos_vel(_spline_time, ref target_pos, ref target_vel); - - // update velocity - float spline_dist_to_wp = (float) (_destination - target_pos).length(); - - // if within the stopping distance from destination, set target velocity to sqrt of distance * 2 * acceleration - if (!_flags.fast_waypoint && spline_dist_to_wp < _slow_down_dist) - { - _spline_vel_scaler = (float) Math.Sqrt(spline_dist_to_wp*2.0f*_wp_accel_cms); - } - else if (_spline_vel_scaler < _wp_speed_cms) - { - // increase velocity using acceleration - // To-Do: replace 0.1f below with update frequency passed in from main program - _spline_vel_scaler += _wp_accel_cms*dt; - } - - // constrain target velocity - if (_spline_vel_scaler > _wp_speed_cms) - { - _spline_vel_scaler = _wp_speed_cms; - } - - // scale the spline_time by the velocity we've calculated vs the velocity that came out of the spline calculator - float spline_time_scale = (float) (_spline_vel_scaler/target_vel.length()); - - // update target position - //_pos_control.set_pos_target(target_pos); - - // update the yaw - _yaw = RadiansToCentiDegrees(atan2(target_vel.y, target_vel.x)); - - // advance spline time to next step - _spline_time += spline_time_scale*dt; - - // 20 segments per spline - // _spline_time +=0.05f; - - // we will reach the next waypoint in the next step so set reached_destination flag - // To-Do: is this one step too early? - if (_spline_time >= 1.0f) - { - _flags.reached_destination = true; - } - } - } - - private float RadiansToCentiDegrees(double p) - { - return (float) (p*MathHelper.rad2deg); - } - - - void calc_spline_pos_vel(float spline_time, ref Vector3 position, ref Vector3 velocity) - { - float spline_time_sqrd = spline_time*spline_time; - float spline_time_cubed = spline_time_sqrd*spline_time; - - position = _hermite_spline_solution[0] + - _hermite_spline_solution[1]*spline_time + - _hermite_spline_solution[2]*spline_time_sqrd + - _hermite_spline_solution[3]*spline_time_cubed; - - velocity = _hermite_spline_solution[1] + - _hermite_spline_solution[2]*2.0f*spline_time + - _hermite_spline_solution[3]*3.0f*spline_time_sqrd; - } - - public double _track_length { get; set; } - } + public double _track_length { get; set; } + } } \ No newline at end of file diff --git a/ExtLibs/Utilities/Warnings/CustomWarning.cs b/ExtLibs/Utilities/Warnings/CustomWarning.cs index 88d84e3d8c..00c25adcc0 100644 --- a/ExtLibs/Utilities/Warnings/CustomWarning.cs +++ b/ExtLibs/Utilities/Warnings/CustomWarning.cs @@ -183,40 +183,45 @@ public bool CheckValue(bool userepeattime = true) if (userepeattime && DateTime.Now < lastrepeat.AddSeconds(RepeatTime)) return false; - lastrepeat = DateTime.Now; + bool condition = false; switch (ConditionType) { case Conditional.EQ: if (GetValue == Warning) - return true; + condition = true; break; case Conditional.GT: if (GetValue > Warning) - return true; + condition = true; break; case Conditional.GTEQ: if (GetValue >= Warning) - return true; + condition = true; break; case Conditional.LT: if (GetValue < Warning) - return true; + condition = true; break; case Conditional.LTEQ: if (GetValue <= Warning) - return true; + condition = true; break; case Conditional.NEQ: if (GetValue != Warning) - return true; + condition = true; break; case Conditional.NONE: break; } - return false; + if (condition) + { + lastrepeat = DateTime.Now; + } + + return condition; } diff --git a/ExtLibs/Utilities/adsb.cs b/ExtLibs/Utilities/adsb.cs index d0d48f4ea6..7d637a17ab 100644 --- a/ExtLibs/Utilities/adsb.cs +++ b/ExtLibs/Utilities/adsb.cs @@ -153,7 +153,7 @@ void TryConnect() // Store start time var timer = Stopwatch.StartNew(); - string formattedUrl = string.Format(url, server, CurrentPosition.Lat, CurrentPosition.Lng, httpRequestRadius); + string formattedUrl = string.Format(CultureInfo.InvariantCulture, url, server, CurrentPosition.Lat, CurrentPosition.Lng, httpRequestRadius); var t = Download.GetAsyncWithStatus(formattedUrl); t.Wait(); diff --git a/GCSViews/ConfigurationView/ConfigSecureAP.cs b/GCSViews/ConfigurationView/ConfigSecureAP.cs index 1e4662b587..c5bb2aa4c5 100644 --- a/GCSViews/ConfigurationView/ConfigSecureAP.cs +++ b/GCSViews/ConfigurationView/ConfigSecureAP.cs @@ -29,14 +29,23 @@ public ConfigSecureAP() private void but_privkey_Click(object sender, System.EventArgs e) { - openFileDialog1.DefaultExt = ".pem"; - openFileDialog1.Filter = "*.pem|*.pem"; + openFileDialog1.DefaultExt = ".pem;.dat"; + openFileDialog1.Filter = "*.pem;*.dat|*.pem;*.dat"; if (openFileDialog1.ShowDialog() == DialogResult.OK) { var pem = File.ReadAllText(openFileDialog1.FileName); - PemReader pr = new PemReader(new StringReader(pem)); - var key = (Ed25519PrivateKeyParameters)pr.ReadObject(); - keyPair = new AsymmetricCipherKeyPair(key.GeneratePublicKey(), key); + if (pem.Contains("PRIVATE_KEYV1")) + { + pem = pem.Replace("PRIVATE_KEYV1:", ""); + var keyap = Convert.FromBase64String(pem); + keyPair = SignedFW.GenerateKey(keyap); + } + else + { + PemReader pr = new PemReader(new StringReader(pem)); + var key = (Ed25519PrivateKeyParameters)pr.ReadObject(); + keyPair = new AsymmetricCipherKeyPair(key.GeneratePublicKey(), key); + } txt_pubkey.Text = Convert.ToBase64String(((Ed25519PublicKeyParameters)keyPair.Public).GetEncoded()); } } @@ -92,6 +101,10 @@ private void but_generatekey_Click(object sender, EventArgs e) if (sfd.ShowDialog() == DialogResult.OK) { File.WriteAllText(sfd.FileName, privatekey); + + File.WriteAllText(sfd.FileName.Replace(".pem", "_private_key.dat"), "PRIVATE_KEYV1:" + Convert.ToBase64String(((Ed25519PrivateKeyParameters)keyPair.Private).GetEncoded())); + File.WriteAllText(sfd.FileName.Replace(".pem", "_public_key.dat"), "PUBLIC_KEYV1:" + Convert.ToBase64String(((Ed25519PublicKeyParameters)keyPair.Public).GetEncoded())); + txt_pubkey.Text = Convert.ToBase64String(((Ed25519PublicKeyParameters)keyPair.Public).GetEncoded()); CustomMessageBox.Show("Protect your private key, if lost there is no method to get it back."); } diff --git a/GCSViews/ConfigurationView/ConfigSerialInjectGPS.cs b/GCSViews/ConfigurationView/ConfigSerialInjectGPS.cs index 5b61b93004..4418d33061 100644 --- a/GCSViews/ConfigurationView/ConfigSerialInjectGPS.cs +++ b/GCSViews/ConfigurationView/ConfigSerialInjectGPS.cs @@ -1480,7 +1480,7 @@ private async void cmb_septentriortcmamount_SelectedIndexChanged(object sender, try { - if (comPort.IsOpen) + if (comPort.IsOpen && comboBoxConfigType.Text == "Septentrio") { await UpdateSeptentrioRTCMSettings(); } @@ -1580,4 +1580,4 @@ private async void chk_septentrioconstellation_Click(object sender, EventArgs e) await UpdateSeptentrioRTCMSettings(); } } -} \ No newline at end of file +} diff --git a/GCSViews/FlightData.Designer.cs b/GCSViews/FlightData.Designer.cs index 03b8f8f3bc..d23a1ff518 100644 --- a/GCSViews/FlightData.Designer.cs +++ b/GCSViews/FlightData.Designer.cs @@ -862,7 +862,7 @@ private void InitializeComponent() 0, 0}); this.modifyandSetAlt.Maximum = new decimal(new int[] { - 1000, + 10000, 0, 0, 0}); diff --git a/GCSViews/FlightData.cs b/GCSViews/FlightData.cs index 63d89bd1a4..2c316f3794 100644 --- a/GCSViews/FlightData.cs +++ b/GCSViews/FlightData.cs @@ -226,6 +226,8 @@ public enum actions {11, "<3m" } }; + private bool transponderNeverConnected = true; + public FlightData() { log.Info("Ctor Start"); @@ -2829,6 +2831,7 @@ private void flightPlannerToolStripMenuItem_Click(object sender, EventArgs e) private void flyToHereAltToolStripMenuItem_Click(object sender, EventArgs e) { string alt = "100"; + MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT; if (MainV2.comPort.MAV.cs.firmware == Firmwares.ArduCopter2) { @@ -2841,11 +2844,14 @@ private void flyToHereAltToolStripMenuItem_Click(object sender, EventArgs e) if (Settings.Instance.ContainsKey("guided_alt")) alt = Settings.Instance["guided_alt"]; + if (Settings.Instance.ContainsKey("guided_alt_frame")) + frame = (MAVLink.MAV_FRAME)byte.Parse(Settings.Instance["guided_alt_frame"]); - if (DialogResult.Cancel == InputBox.Show("Enter Alt", "Enter Guided Mode Alt", ref alt)) + if (DialogResult.Cancel == AltInputBox.Show("Enter Alt", "Enter Guided Mode Alt", ref alt, ref frame)) return; Settings.Instance["guided_alt"] = alt; + Settings.Instance["guided_alt_frame"] = ((byte)frame).ToString(); int intalt = (int) (100 * CurrentState.multiplieralt); if (!int.TryParse(alt, out intalt)) @@ -2855,6 +2861,7 @@ private void flyToHereAltToolStripMenuItem_Click(object sender, EventArgs e) } MainV2.comPort.MAV.GuidedMode.z = intalt / CurrentState.multiplieralt; + MainV2.comPort.MAV.GuidedMode.frame = (byte) frame; if (MainV2.comPort.MAV.cs.mode == "Guided") { @@ -2862,7 +2869,8 @@ private void flyToHereAltToolStripMenuItem_Click(object sender, EventArgs e) { alt = MainV2.comPort.MAV.GuidedMode.z, lat = MainV2.comPort.MAV.GuidedMode.x / 1e7, - lng = MainV2.comPort.MAV.GuidedMode.y / 1e7 + lng = MainV2.comPort.MAV.GuidedMode.y / 1e7, + frame = (byte)frame }); } } @@ -3017,6 +3025,7 @@ private void goHereToolStripMenuItem_Click(object sender, EventArgs e) gotohere.alt = MainV2.comPort.MAV.GuidedMode.z; // back to m gotohere.lat = (MouseDownStart.Lat); gotohere.lng = (MouseDownStart.Lng); + gotohere.frame = MainV2.comPort.MAV.GuidedMode.frame; try { @@ -3289,6 +3298,8 @@ private void mainloop() DateTime updatescreen = DateTime.Now; + DateTime transponderUpdate = DateTime.Now; + DateTime tsreal = DateTime.Now; double taketime = 0; double timeerror = 0; @@ -4196,9 +4207,10 @@ private void mainloop() Console.WriteLine("FD Main loop exception " + ex); } - if (MainV2.comPort.MAV.cs.xpdr_status_pending) + if (MainV2.comPort.MAV.cs.xpdr_status_pending || transponderUpdate.AddMilliseconds(5000) < DateTime.Now) { BeginInvoke((Action) updateTransponder); + transponderUpdate = DateTime.Now; } } @@ -5826,6 +5838,16 @@ private void flyToCoordsToolStripMenuItem_Click(object sender, EventArgs e) var location = ""; InputBox.Show("Enter Fly To Coords", "Please enter the coords 'lat;long;alt' or 'lat;long'", ref location); + byte frame = (byte)MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT; + if (!MainV2.comPort.MAV.GuidedMode.Equals(new MAVLink.mavlink_mission_item_int_t())) + { + frame = MainV2.comPort.MAV.GuidedMode.frame; + } + else if (Settings.Instance.ContainsKey("guided_alt_frame")) + { + byte.TryParse(Settings.Instance["guided_alt_frame"], out frame); + } + var split = location.Split(';'); if (split.Length == 3) @@ -5842,6 +5864,7 @@ private void flyToCoordsToolStripMenuItem_Click(object sender, EventArgs e) gotohere.alt = (float) plla.Alt / CurrentState.multiplieralt; // back to m gotohere.lat = (plla.Lat); gotohere.lng = (plla.Lng); + gotohere.frame = frame; try { @@ -5866,6 +5889,7 @@ private void flyToCoordsToolStripMenuItem_Click(object sender, EventArgs e) gotohere.alt = MainV2.comPort.MAV.GuidedMode.z; // back to m gotohere.lat = (plla.Lat); gotohere.lng = (plla.Lng); + gotohere.frame = frame; try { @@ -6230,7 +6254,7 @@ private void XPDRConnect_btn_Click(object sender, EventArgs e) { updateTransponder(); } - else CustomMessageBox.Show("Timeout."); + else CustomMessageBox.Show("Timeout: Status message not received."); } catch (Exception ex) @@ -6241,9 +6265,40 @@ private void XPDRConnect_btn_Click(object sender, EventArgs e) private void updateTransponder() { - MainV2.comPort.MAV.cs.xpdr_status_pending = false; - if (!MainV2.comPort.MAV.cs.xpdr_status_unavail) + if (!MainV2.comPort.MAV.cs.xpdr_status_pending) { + // timeout on status message + STBY_btn.Enabled = false; + ON_btn.Enabled = false; + ALT_btn.Enabled = false; + IDENT_btn.Enabled = false; + FlightID_tb.Enabled = false; + Squawk_nud.Enabled = false; + + if (transponderNeverConnected) + { + XPDRConnect_btn.Text = "Connect To Transponder"; + XPDRConnect_btn.Enabled = true; + } + else + { + // if we have connected before, we should have subscribed to the status message. + // something must have reset the message interval (AP power cycled, etc.) + // so indicate that the connection reset + XPDRConnect_btn.Text = "Transponder Status Lost"; + XPDRConnect_btn.Enabled = true; + transponderNeverConnected = true; + } + } + else if (!MainV2.comPort.MAV.cs.xpdr_status_unavail) + { + if (transponderNeverConnected) + { + // subscribe to status message on first connection + MainV2.comPort.doCommand(MAVLink.MAV_CMD.SET_MESSAGE_INTERVAL, (float) MAVLink.MAVLINK_MSG_ID.UAVIONIX_ADSB_OUT_STATUS, (float) 1000000.0, 0, 0, 0, 0, 0); + transponderNeverConnected = false; + } + STBY_btn.Enabled = true; ON_btn.Enabled = true; ALT_btn.Enabled = true; @@ -6262,8 +6317,8 @@ private void updateTransponder() !Mode_clb.GetItemChecked(2) && !Mode_clb.GetItemChecked(3)) ? FontStyle.Bold : FontStyle.Regular); ON_btn.Font = new Font(ON_btn.Font, ( Mode_clb.GetItemChecked(0) && - Mode_clb.GetItemChecked(1) && - !Mode_clb.GetItemChecked(2) && + !Mode_clb.GetItemChecked(1) && + Mode_clb.GetItemChecked(2) && Mode_clb.GetItemChecked(3)) ? FontStyle.Bold : FontStyle.Regular); ALT_btn.Font = new Font(ALT_btn.Font, ( Mode_clb.GetItemChecked(0) && Mode_clb.GetItemChecked(1) && @@ -6304,6 +6359,7 @@ private void updateTransponder() IDENT_btn.Font = new Font(IDENT_btn.Font, MainV2.comPort.MAV.cs.xpdr_ident_active ? FontStyle.Bold : FontStyle.Regular); XPDRConnect_btn.Text = "Transponder Connected!"; + XPDRConnect_btn.Enabled = false; } else { @@ -6314,8 +6370,10 @@ private void updateTransponder() FlightID_tb.Enabled = false; Squawk_nud.Enabled = false; - XPDRConnect_btn.Text = "Connect to Transponder"; + XPDRConnect_btn.Text = "Transponder Offline"; + XPDRConnect_btn.Enabled = false; } + MainV2.comPort.MAV.cs.xpdr_status_pending = false; } private void showIconsToolStripMenuItem_Click(object sender, EventArgs e) diff --git a/GCSViews/FlightPlanner.cs b/GCSViews/FlightPlanner.cs index 8fa04b5247..7b75cb6816 100644 --- a/GCSViews/FlightPlanner.cs +++ b/GCSViews/FlightPlanner.cs @@ -53,6 +53,7 @@ using MissionPlanner.ArduPilot.Mavlink; using System.Drawing.Imaging; using SharpKml.Engine; +using MissionPlanner.Controls.Waypoints; namespace MissionPlanner.GCSViews { @@ -5175,12 +5176,22 @@ private void processKML(Element Element, Document root = null) { if (((Style)style).Line != null) { - int color = ((Style)style).Line.Color.Value.Abgr; + int color; + if (((Style)style).Line.Color != null) + { + color = ((Style)style).Line.Color.Value.Abgr; + color = (int)((color & 0xFF00FF00) | ((color & 0x00FF0000) >> 16) | ((color & 0x000000FF) << 16)); + + } + else color = Color.White.ToArgb(); // convert color from ABGR to ARGB - color = (int)((color & 0xFF00FF00) | ((color & 0x00FF0000) >> 16) | ((color & 0x000000FF) << 16)); - // ABGR - return (Color.FromArgb(color), (int)((Style)style).Line.Width.Value); + if (((Style)style).Line.Width != null) + { + return (Color.FromArgb(color), (int)((Style)style).Line.Width.Value); + } + else + return (Color.FromArgb(color), 2); } } } @@ -5318,6 +5329,21 @@ private void processToScreen(List cmds, bool append = false) temp.id == (ushort) MAVLink.MAV_CMD.SPLINE_WAYPOINT || temp.id == (ushort) MAVLink.MAV_CMD.TAKEOFF || temp.id == (ushort) MAVLink.MAV_CMD.DO_SET_HOME) { + + try + { + // cm/s - ac + Spline2._wp_accel_cms = MainV2.comPort.MAV.param.ContainsKey("WPNAV_ACCEL") ? MainV2.comPort.MAV.param["WPNAV_ACCEL"].float_value : 100; + Spline2._wp_speed_cms = MainV2.comPort.MAV.param.ContainsKey("WPNAV_SPEED") ? MainV2.comPort.MAV.param["WPNAV_SPEED"].float_value : 600; + + // ar + //WP_ACCEL - m/s + //WP_SPEED - m/s + } + catch + { + + } // not home if (i != 0) { diff --git a/GCSViews/InitialSetup.cs b/GCSViews/InitialSetup.cs index 0c3b359daa..e323dcfe20 100644 --- a/GCSViews/InitialSetup.cs +++ b/GCSViews/InitialSetup.cs @@ -6,6 +6,7 @@ using MissionPlanner.Radio; using MissionPlanner.Utilities; using System; +using System.Collections.Generic; using System.Reflection; using System.Resources; using System.Windows.Forms; @@ -17,6 +18,44 @@ public partial class InitialSetup : MyUserControl, IActivate internal static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); private static string lastpagename = ""; + [Flags] + public enum pageOptions + { + none = 0, + isConnected = 1, + isDisConnected = 2, + isTracker = 4, + isCopter = 8, + isCopter35plus = 16, + isHeli = 32, + isQuadPlane = 64, + isPlane = 128, + isRover = 256, + gotAllParams = 512 + } + + public class pluginPage + { + public Type page; + public string headerText; + public pageOptions options; + + public pluginPage(Type page, string headerText, pageOptions options) + { + this.page = page; + this.headerText = headerText; + this.options = options; + } + } + + + private static List pluginViewPages = new List(); + public static void AddPluginViewPage(Type page, string headerText, pageOptions options = pageOptions.none) + { + pluginViewPages.Add(new pluginPage(page, headerText, options)); + } + + public InitialSetup() { InitializeComponent(); @@ -92,7 +131,7 @@ public bool gotAllParams } } - private BackstageViewPage AddBackstageViewPage(Type userControl, string headerText, bool enabled = true, + public BackstageViewPage AddBackstageViewPage(Type userControl, string headerText, bool enabled = true, BackstageViewPage Parent = null, bool advanced = false) { try @@ -138,7 +177,7 @@ private void HardwareConfig_Load(object sender, EventArgs e) AddBackstageViewPage(typeof(ConfigSecureAP), "Secure", isDisConnected); - + var mand = AddBackstageViewPage(typeof(ConfigMandatory), rm.GetString("backstageViewPagemand.Text"), isConnected && gotAllParams); @@ -309,6 +348,35 @@ private void HardwareConfig_Load(object sender, EventArgs e) } } + + foreach (var item in pluginViewPages) + { + + // go through all options + if (item.options.HasFlag(pageOptions.isConnected) && !isConnected) + continue; + if (item.options.HasFlag(pageOptions.isDisConnected) && !isDisConnected) + continue; + if (item.options.HasFlag(pageOptions.isTracker) && !isTracker) + continue; + if (item.options.HasFlag(pageOptions.isCopter) && !isCopter) + continue; + if (item.options.HasFlag(pageOptions.isCopter35plus) && !isCopter35plus) + continue; + if (item.options.HasFlag(pageOptions.isHeli) && !isHeli) + continue; + if (item.options.HasFlag(pageOptions.isQuadPlane) && !isQuadPlane) + continue; + if (item.options.HasFlag(pageOptions.isPlane) && !isPlane) + continue; + if (item.options.HasFlag(pageOptions.isRover) && !isRover) + continue; + if (item.options.HasFlag(pageOptions.gotAllParams) && !gotAllParams) + continue; + + AddBackstageViewPage(item.page, item.headerText); + } + // remeber last page accessed foreach (BackstageViewPage page in backstageView.Pages) { diff --git a/GCSViews/SoftwareConfig.cs b/GCSViews/SoftwareConfig.cs index 9025b91979..644a7ac68b 100644 --- a/GCSViews/SoftwareConfig.cs +++ b/GCSViews/SoftwareConfig.cs @@ -5,6 +5,7 @@ using MissionPlanner.GCSViews.ConfigurationView; using MissionPlanner.Utilities; using System; +using System.Collections.Generic; using System.Reflection; using System.Windows.Forms; @@ -13,7 +14,93 @@ namespace MissionPlanner.GCSViews public partial class SoftwareConfig : MyUserControl, IActivate { internal static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); - private static string lastpagename = ""; + private static string lastpagename = ""; + [Flags] + public enum pageOptions + { + none = 0, + isConnected = 1, + isDisConnected = 2, + isTracker = 4, + isCopter = 8, + isCopter35plus = 16, + isHeli = 32, + isQuadPlane = 64, + isPlane = 128, + isRover = 256, + gotAllParams = 512 + } + + public class pluginPage + { + public Type page; + public string headerText; + public pageOptions options; + + public pluginPage(Type page, string headerText, pageOptions options) + { + this.page = page; + this.headerText = headerText; + this.options = options; + } + } + + + private static List pluginViewPages = new List(); + + public static void AddPluginViewPage(Type page, string headerText, pageOptions options = pageOptions.none) + { + pluginViewPages.Add(new pluginPage(page, headerText, options)); + } + public bool isConnected + { + get { return MainV2.comPort.BaseStream.IsOpen; } + } + public bool isTracker + { + get { return isConnected && MainV2.comPort.MAV.cs.firmware == Firmwares.ArduTracker; } + } + + public bool isCopter + { + get { return isConnected && MainV2.comPort.MAV.cs.firmware == Firmwares.ArduCopter2; } + } + + public bool isCopter35plus + { + get { return MainV2.comPort.MAV.cs.version >= Version.Parse("3.5"); } + } + + public bool isHeli + { + get { return isConnected && MainV2.comPort.MAV.aptype == MAVLink.MAV_TYPE.HELICOPTER; } + } + + public bool isQuadPlane + { + get + { + return isConnected && isPlane && + MainV2.comPort.MAV.param.ContainsKey("Q_ENABLE") && + (MainV2.comPort.MAV.param["Q_ENABLE"].Value == 1.0); + } + } + + public bool isPlane + { + get + { + return isConnected && + (MainV2.comPort.MAV.cs.firmware == Firmwares.ArduPlane || + MainV2.comPort.MAV.cs.firmware == Firmwares.Ateryx); + } + } + + public bool isRover + { + get { return isConnected && MainV2.comPort.MAV.cs.firmware == Firmwares.ArduRover; } + } + public bool gotAllParams { @@ -38,7 +125,7 @@ public void Activate() { } - private BackstageViewPage AddBackstageViewPage(Type userControl, string headerText, + public BackstageViewPage AddBackstageViewPage(Type userControl, string headerText, BackstageViewPage Parent = null, bool advanced = false) { try @@ -169,7 +256,36 @@ private void SoftwareConfig_Load(object sender, EventArgs e) { start = AddBackstageViewPage(typeof(ConfigPlanner), Strings.Planner); } - } + } + + // Add custrom pages set up by plugins + foreach (var item in pluginViewPages) + { + + // go through all options expect disconnected since there is no meaning for sw config in disconnected state + if (item.options.HasFlag(pageOptions.isConnected) && !isConnected) + continue; + if (item.options.HasFlag(pageOptions.isTracker) && !isTracker) + continue; + if (item.options.HasFlag(pageOptions.isCopter) && !isCopter) + continue; + if (item.options.HasFlag(pageOptions.isCopter35plus) && !isCopter35plus) + continue; + if (item.options.HasFlag(pageOptions.isHeli) && !isHeli) + continue; + if (item.options.HasFlag(pageOptions.isQuadPlane) && !isQuadPlane) + continue; + if (item.options.HasFlag(pageOptions.isPlane) && !isPlane) + continue; + if (item.options.HasFlag(pageOptions.isRover) && !isRover) + continue; + if (item.options.HasFlag(pageOptions.gotAllParams) && !gotAllParams) + continue; + + AddBackstageViewPage(item.page, item.headerText); + } + + // apply theme before trying to display it ThemeManager.ApplyThemeTo(this); diff --git a/MainV2.cs b/MainV2.cs index 41bd9f4f59..18b346d2ab 100644 --- a/MainV2.cs +++ b/MainV2.cs @@ -747,12 +747,6 @@ public MainV2() { } - Warnings.CustomWarning.defaultsrc = comPort.MAV.cs; - Warnings.WarningEngine.Start(speechEnable ? speechEngine : null); - Warnings.WarningEngine.WarningMessage += (sender, s) => { MainV2.comPort.MAV.cs.messageHigh = s; }; - - Warnings.WarningEngine.QuickPanelColoring += WarningEngine_QuickPanelColoring; - // proxy loader - dll load now instead of on config form load new Transition(new TransitionType_EaseInEaseOut(2000)); @@ -1021,6 +1015,11 @@ public MainV2() { } + Warnings.CustomWarning.defaultsrc = comPort.MAV.cs; + Warnings.WarningEngine.Start(speechEnable ? speechEngine : null); + Warnings.WarningEngine.WarningMessage += (sender, s) => { MainV2.comPort.MAV.cs.messageHigh = s; }; + Warnings.WarningEngine.QuickPanelColoring += WarningEngine_QuickPanelColoring; + if (CurrentState.rateattitudebackup == 0) // initilised to 10, configured above from save { CustomMessageBox.Show("NOTE: your attitude rate is 0, the hud will not work\nChange in Configuration > Planner > Telemetry Rates"); @@ -1681,8 +1680,8 @@ public void doConnect(MAVLinkInterface comPort, string portname, string baud, bo foreach (var item in softwares) { - // check primare firmware type. ie arudplane, arducopter - if (fields1[0].ToLower().Contains(item.VehicleType.ToLower())) + // check primare firmware type. ie arudplane, arducopter + if (fields1[0].ToLower().Contains(item.VehicleType.ToLower())) { Version ver1 = VersionDetection.GetVersion(comPort.MAV.VersionString); Version ver2 = item.MavFirmwareVersion; @@ -1695,10 +1694,13 @@ public void doConnect(MAVLinkInterface comPort, string portname, string baud, bo break; } - // check the first hit only - break; + // check the first hit only + break; } } + + // load version specific config + ParameterMetaDataRepositoryAPMpdef.GetMetaDataVersioned(VersionDetection.GetVersion(comPort.MAV.VersionString)); } catch (Exception ex) { diff --git a/MissionPlanner.csproj b/MissionPlanner.csproj index 882b3916c8..084c1408b4 100644 --- a/MissionPlanner.csproj +++ b/MissionPlanner.csproj @@ -391,6 +391,12 @@ Always + + Always + + + Always + UserControl @@ -1181,4 +1187,7 @@ + + + \ No newline at end of file diff --git a/Plugins/example22-payloadconfig.cs b/Plugins/example22-payloadconfig.cs new file mode 100644 index 0000000000..bc1e93a807 --- /dev/null +++ b/Plugins/example22-payloadconfig.cs @@ -0,0 +1,265 @@ +using System; +using System.Collections.Generic; +using System.Windows.Forms; +using MissionPlanner.Controls; +using MissionPlanner.GCSViews; +using MissionPlanner.Plugin; +using log4net; + +namespace MissionPlanner.plugins +{ +/// +/// This plugin adds a "Payload Selection" page to Mission Planner's Config tab. +/// It allows users to select various payload configurations, such as gimbals or cameras, +/// by checking boxes associated with each payload type. Each payload setting adjusts +/// specific parameters and reverts to defaults when unchecked. Parameter adjustments +/// are only allowed while the vehicle is disarmed. +/// +/// ### WARNING: +/// This is a simple example plugin with minimal testing and limited error handling. +/// It is recommended to review and test this code thoroughly in a safe environment +/// before relying on it in operational settings. +/// +/// ### Modifying the Plugin: +/// - To enable this plugin, add payloads to the `payloadParameters` dictionary. If +/// the dictionary is empty, the plugin will not initialize. +/// - To add new payloads, modify the `payloadParameters` dictionary with the desired +/// payload name as the key and a dictionary of parameter settings as the value. +/// - Example: Adding a new payload: +/// { "NewPayload", new Dictionary { { "PARAM_NAME", value } } } +/// - Each payload’s parameters are activated when checked and reverted to their default +/// when unchecked, if defaults exist. +/// + public class example22_payloadconfig : Plugin.Plugin + { + public override string Name => "Payload Select Page"; + public override string Version => "0.1"; + public override string Author => "Bob Long"; + + + // DEFINE YOUR PAYLOADS, AND THEIR PARAMETERS, HERE + public static readonly Dictionary> payloadParameters = new Dictionary> + { + // { + // "Gimbal", new Dictionary + // { + // { "MNT1_TYPE", 9}, // Set Mount1 Type to Scripting + // } + // }, + // { + // "Mapping Camera", new Dictionary + // { + // { "CAM_TRIGG_TYPE", 1 }, // Set trigger type to PWM + // { "SERVO9_FUNCTION", 10 }, // Set servo 9 to camera trigger + // } + // } + }; + + private CheckedListBox payloadCheckboxList; + + public override bool Init() + { + // Only initialize the plugin if payloads have been configured. + return payloadParameters.Count > 0; + } + + public override bool Loaded() + { + // Register the ConfigPayload view on the Config tab + SoftwareConfig.AddPluginViewPage(typeof(ConfigPayload), "Payload Selection", SoftwareConfig.pageOptions.isConnected | SoftwareConfig.pageOptions.gotAllParams); + + return true; + } + + public override bool Exit() { return true; } + } + + public class ConfigPayload : MyUserControl, IActivate + { + private Dictionary> payloadParameters = example22_payloadconfig.payloadParameters; + private readonly CheckedListBox payloadCheckboxList; + private readonly static ILog log = LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); + + /// + /// Initializes the ConfigPayload control with a checklist of available payload selections. + /// + public ConfigPayload() + { + // Initialize CheckedListBox for payload selection + payloadCheckboxList = new CheckedListBox + { + CheckOnClick = true, + Dock = DockStyle.Left, + }; + + // Add payload options as checkboxes + foreach (var payload in payloadParameters.Keys) + { + payloadCheckboxList.Items.Add(payload); + } + + // Handle check state changes + payloadCheckboxList.ItemCheck += PayloadCheckboxList_ItemCheck; + + // Add the CheckedListBox to the control + Controls.Add(payloadCheckboxList); + } + + /// + /// Called when the ConfigPayload view is activated. + /// + public void Activate() + { + UpdateCheckboxState(); + CheckArmed(); + } + + /// + /// Checks if the vehicle is armed, disables the checkbox list and warns the user if it is. + /// + private void CheckArmed() + { + payloadCheckboxList.Enabled = !MainV2.comPort.MAV.cs.armed; + if (MainV2.comPort.MAV.cs.armed) + { + CustomMessageBox.Show("The vehicle is armed. Payload selection is disabled.", "Payload Selection"); + } + } + + /// + /// Updates the checked state of each checkbox based on current parameter values. + /// If all parameters for a payload match the predefined values, the checkbox is checked. + /// + private void UpdateCheckboxState() + { + for (int i = 0; i < payloadCheckboxList.Items.Count; i++) + { + string payload = payloadCheckboxList.Items[i].ToString(); + if (IsPayloadActive(payloadParameters[payload])) + { + payloadCheckboxList.SetItemChecked(i, true); + } + } + } + + /// + /// Checks if all parameters in the vehicle match a given dictionary. + /// + /// Dictionary of parameter names and values + /// True if all parameters match, false otherwise. + private bool IsPayloadActive(Dictionary parameters) + { + foreach (var param in parameters) + { + if (!MainV2.comPort.MAV.param.ContainsKey(param.Key)) + { + log.Warn($"Parameter {param.Key} not found for comparison."); + return false; + } + if (!ParamEquality(MainV2.comPort.MAV.param[param.Key].Value, param.Value)) + { + return false; + } + } + return true; + } + + /// + /// Handles checkbox state changes, applying or reverting parameters based on the checked state. + /// + private void PayloadCheckboxList_ItemCheck(object sender, ItemCheckEventArgs e) + { + CheckArmed(); + + string payload = payloadCheckboxList.Items[e.Index].ToString(); + var parameters = payloadParameters[payload]; + + if (e.NewValue == CheckState.Checked) + { + ApplyPayloadParameters(parameters); + } + else + { + RevertParametersToDefault(parameters); + } + } + + /// + /// Applies the specified parameters. + /// + /// Dictionary of parameter names and values to set. + private void ApplyPayloadParameters(Dictionary parameters) + { + foreach (var param in parameters) + { + MainV2.comPort.setParam(param.Key, param.Value); + } + + if (CheckParamCountChanged() && parameters.Count > 1) + { + // Apply parameters again (we assume there will not be nested enable params for this plugin) + foreach (var param in parameters) + { + MainV2.comPort.setParam(param.Key, param.Value); + } + } + } + + /// + /// Checks if the parameter count has changed, which might indicate new parameters were added. + /// If so, triggers a parameter list refresh and logs the update. + /// + private bool CheckParamCountChanged() + { + if (MainV2.comPort.MAV.param.TotalReceived != MainV2.comPort.MAV.param.TotalReported) + { + CustomMessageBox.Show("The number of available parameters changed. A full param refresh will be done.", "Params"); + try + { + MainV2.comPort.getParamList(); + } + catch (Exception ex) + { + log.Error("Exception getting param list", ex); + CustomMessageBox.Show(Strings.ErrorReceivingParams, Strings.ERROR); + } + return true; + } + return false; + } + + /// + /// Reverts parameters for an unchecked payload to their default values. + /// + /// Dictionary of parameter names and expected default values. + private void RevertParametersToDefault(Dictionary parameters) + { + foreach (var param in parameters) + { + if (!MainV2.comPort.MAV.param.ContainsKey(param.Key)) + { + log.Warn($"Parameter {param.Key} missing during revert to default."); + continue; + } + if (MainV2.comPort.MAV.param[param.Key].default_value == null) + { + log.Warn($"No default value found for parameter {param.Key}"); + continue; + } + // This doesn't technically reset params if they get hidden after an enable param changes, + // but that is okay for our purposes. + MainV2.comPort.setParam(param.Key, MainV2.comPort.MAV.param[param.Key].default_value.Value); + } + + CheckParamCountChanged(); + } + + /// + /// Checks if two parameter values are equal within a small tolerance. + /// + private bool ParamEquality(double a, double b) + { + return Math.Abs(a - b) < Math.Max(1e-6, Math.Max(Math.Abs(a), Math.Abs(b)) * 1e-6); + } + } +} diff --git a/Plugins/example23-switch.cs b/Plugins/example23-switch.cs new file mode 100644 index 0000000000..115653103b --- /dev/null +++ b/Plugins/example23-switch.cs @@ -0,0 +1,468 @@ +using System; +using System.Collections.Generic; +using System.Windows.Forms; +using MissionPlanner.Controls; +using MissionPlanner.GCSViews; +using MissionPlanner.Plugin; +using log4net; +using System.Linq; +using DeviceProgramming; +using System.Threading; +using Xamarin.Forms.PlatformConfiguration; + +//loadassembly: DeviceProgramming +//loadassembly: log4net + +namespace MissionPlanner.plugins +{ + public class ConfigSwitch : UserControl, IActivate + { + private readonly static ILog log = LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); + + public struct Command + { + public byte phyaddress; + public byte register; + public byte highbyte; + public byte lowbyte; + } + + const ushort CommandStart = 0x55aa; + List CommandList = new List(); + private TableLayoutPanel tableLayoutPanel1; + const ushort CommandEnd = 0xaa55; + + public enum phyaddress + { + cos = 21, // class of service + EEE = 22, // Energy Efficient Ethernet + vlan = 23, // Virtual Local Area Network + } + + /// + /// Initializes the ConfigPayload control with a checklist of available payload selections. + /// + public ConfigSwitch() + { + InitializeComponent(); + } + + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + + private void InitializeComponent() + { + this.tableLayoutPanel1 = new System.Windows.Forms.TableLayoutPanel(); + this.SuspendLayout(); + // + // tableLayoutPanel1 + // + this.tableLayoutPanel1.ColumnCount = 8; + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.ColumnStyles.Add(new System.Windows.Forms.ColumnStyle(System.Windows.Forms.SizeType.Percent, 12.5F)); + this.tableLayoutPanel1.Dock = System.Windows.Forms.DockStyle.Fill; + this.tableLayoutPanel1.Location = new System.Drawing.Point(0, 0); + this.tableLayoutPanel1.Name = "tableLayoutPanel1"; + this.tableLayoutPanel1.RowCount = 13; + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.RowStyles.Add(new System.Windows.Forms.RowStyle(System.Windows.Forms.SizeType.Absolute, 40F)); + this.tableLayoutPanel1.Size = new System.Drawing.Size(596, 322); + this.tableLayoutPanel1.TabIndex = 0; + // + // ConfigSwitch + // + this.Controls.Add(this.tableLayoutPanel1); + this.Name = "ConfigSwitch"; + this.Size = new System.Drawing.Size(596, 322); + this.ResumeLayout(false); + + } + + /// + /// Called when the ConfigPayload view is activated. + /// + public void Activate() + { + tableLayoutPanel1.PerformLayout(); + + tableLayoutPanel1.RowCount = 13; + for (int a = 0; a <= 7; a++) + { + CheckBox cbcos = new CheckBox(); + cbcos.Text = "Port " + a + " COS Enable"; + + cbcos.Tag = (21, a, 10); + + tableLayoutPanel1.Controls.Add(cbcos); + + cbcos.CheckedChanged += (s, e) => { + var data = (ValueTuple)cbcos.Tag; + ProcessCmd(data, cbcos.Checked); + }; + + SetDefault(cbcos, false); + } + + for (int a = 0; a <= 7; a++) + { + CheckBox cbcoshp = new CheckBox(); + cbcoshp.Text = "Port " + a + " COS High Priority"; + cbcoshp.Tag = (21, a, 11); + + tableLayoutPanel1.Controls.Add(cbcoshp); + + cbcoshp.CheckedChanged += (s, e) => { + var data = (ValueTuple)cbcoshp.Tag; + ProcessCmd(data, cbcoshp.Checked); + }; + + SetDefault(cbcoshp, false); + } + + for (int a = 0; a <= 7; a++) + { + CheckBox cbeee = new CheckBox(); + + cbeee.Text = "Port " + a + " EEE Enable"; + cbeee.Tag = (22, 0, a); + + tableLayoutPanel1.Controls.Add(cbeee); + + cbeee.CheckedChanged += (s, e) => { + var data = (ValueTuple)cbeee.Tag; + ProcessCmd(data, cbeee.Checked); + }; + + SetDefault(cbeee, true); + } + + for (int a = 0; a <= 7; a++) + { + CheckBox cbtagged = new CheckBox(); + cbtagged.Checked = false; + + cbtagged.Text = "Port " + a + " VLAN Tagged"; + + cbtagged.Tag = (23, 13, a); + + tableLayoutPanel1.Controls.Add(cbtagged); + + cbtagged.CheckedChanged += (s, e) => { + var data = (ValueTuple)cbtagged.Tag; + ProcessCmd(data, cbtagged.Checked); + }; + + SetDefault(cbtagged, false); + } + + for (int port = 0; port <= 7; port++) + { + for (int a = 0; a <= 7; a++) + { + CheckBox cbvlanportmembers = new CheckBox(); + + cbvlanportmembers.Text = "Port " + port + " to Port " + a + " "; + + var high = (int)(port / 2); + var align = port % 2; + + cbvlanportmembers.Tag = (23, 15 + high, a + (align == 1 ? 8 : 0)); + + tableLayoutPanel1.Controls.Add(cbvlanportmembers); + + cbvlanportmembers.CheckedChanged += (s, e) => + { + var data = (ValueTuple)cbvlanportmembers.Tag; + ProcessCmd(data, cbvlanportmembers.Checked); + }; + + SetDefault(cbvlanportmembers, true); + } + } + + MyButton btn = new MyButton(); + btn.Text = "Apply"; + btn.Click += (s, e) => + { + Apply(); + }; + tableLayoutPanel1.Controls.Add(btn); + + MyButton btn2 = new MyButton(); + btn2.Text = "Reset"; + btn2.Click += (s, e) => + { + CommandList.Clear(); + Apply(); + }; + tableLayoutPanel1.Controls.Add(btn2); + + var buffer = new byte[100]; + var result = MainV2.comPort.device_op(1, 1, out buffer, + MAVLink.DEVICE_OP_BUSTYPE.I2C, + "", 0, 80, + 0, (byte)buffer.Length); + + if (result != 0) + { + this.Enabled = false; + return; + } + // load save config + decode(buffer); + + tableLayoutPanel1.Controls.Add(new Label() { Text = buffer.Select(a => a.ToString("X2")).Aggregate((a, b) => a + b) }); + tableLayoutPanel1.Controls.Add(new Label() { Text = "i2c2 only" }); + + // restore config + foreach (var item in tableLayoutPanel1.Controls) + { + if(item is CheckBox) + { + SetDefaultFromConfig((CheckBox)item); + } + } + } + + private void SetDefault(CheckBox cbcontrol, bool @default) + { + // set the default + cbcontrol.Checked = @default; + // create the config + var data = (ValueTuple)cbcontrol.Tag; + ProcessCmd(data, @default); + } + + private void SetDefaultFromConfig(CheckBox cbcontrol) + { + var data = (ValueTuple)cbcontrol.Tag; + // get the saved default + var newdefault = ProcessCmdGet(data); + + cbcontrol.Checked = newdefault; + } + + private void decode(byte[] buffer) + { + var work = buffer.AsSpan(); + if (buffer[0] == 0xaa && buffer[1] == 0x55) + { + // drop header + work = work.Slice(2); + while(work.Length > 3) + { + var phy = work[0]; + var reg = work[1]; + if (work[0] == 0x55 && work[1] == 0xaa) + break; + var value = (work[2] << 8) + work[3]; + + var command = new Command() { phyaddress = phy, register = reg, highbyte = work[2], lowbyte = work[3] }; + + log.InfoFormat("phy {0} {1} reg {2} value {3}", phy, (phyaddress)phy, reg, value); + + work = work.Slice(4); + + // add to list - replace existing + var item = CommandList.Where(a => a.phyaddress == command.phyaddress && a.register == command.register); + if (item.Count() > 0) + CommandList.Remove(item.First()); + + CommandList.Add(command); + } + } + } + + private void Apply() + { + var start = BitConverter.GetBytes(CommandStart); + var end = BitConverter.GetBytes(CommandEnd); + + var data = new List(); + data.AddRange(start); + + CommandList.Sort((a, b) => + { + var cmp1 = a.phyaddress.CompareTo(b.phyaddress); + var cmp2 = a.register.CompareTo(b.register); + if (cmp1 != 0) + return cmp1; + return cmp2; + }); + + CommandList.ForEach(a => data.AddRange(a.ToBytes())); + + data.AddRange(end); + + data.AddRange(BitConverter.GetBytes(0xffffffff)); + + byte count = 1; + var buffer = new byte[count]; + + var offset = 0; + foreach (var item in data) + { + again: + + // read it + var result = MainV2.comPort.device_op(1, 1, out buffer, + MAVLink.DEVICE_OP_BUSTYPE.I2C, + "", 0, 80, + (byte)offset, 1); + + if (result != 0 || buffer.Length == 0) + goto again; + + // skip already set + if (buffer[0] == item) + { + offset++; + continue; + } + + // write it + result = MainV2.comPort.device_op(1, 1, out buffer, + MAVLink.DEVICE_OP_BUSTYPE.I2C, + "", 0, 80, + (byte)offset, 0, new[] { item }); + + if (result != 0) + { + log.Error("bad i2c op " + result); + goto again; + } + + goto again; + } + } + + int SetBitTo1(int value, int position) + { + return value |= (1 << position); + } + + int SetBitTo0(int value, int position) + { + return value & ~(1 << position); + } + + bool IsBitSetTo1(int value, int position) + { + // Return whether bit at position is set to 1. + return (value & (1 << position)) != 0; + } + + bool IsBitSetTo0(int value, int position) + { + // If not 1, bit is 0. + return !IsBitSetTo1(value, position); + } + + private void ProcessCmd((int, int, int) data, bool @checked) + { + // update + if (CommandList.Any(a => a.phyaddress == data.Item1 && a.register == data.Item2)) + { + var item = CommandList.First(a => a.phyaddress == data.Item1 && a.register == data.Item2); + CommandList.Remove(item); + + var value = (item.highbyte << 8) + item.lowbyte; + + if (@checked) + value = (ushort)SetBitTo1(value, data.Item3); + else + value = (ushort)SetBitTo0(value, data.Item3); + + item.highbyte = (byte)(value >> 8); + item.lowbyte = (byte)(value & 0xff); + + CommandList.Add(item); + } + else + { + //add + var value = (ushort)((@checked ? 1 : 0) << data.Item3); + + CommandList.Add(new Command() + { + phyaddress = (byte)data.Item1, + register = (byte)data.Item2, + highbyte = (byte)(value >> 8), + lowbyte = (byte)(value & 0xff) + }); + } + } + + private bool ProcessCmdGet((int, int, int) data) + { + if (CommandList.Any(a => a.phyaddress == data.Item1 && a.register == data.Item2)) + { + var item = CommandList.First(a => a.phyaddress == data.Item1 && a.register == data.Item2); + + var value = (item.highbyte << 8) + item.lowbyte; + + var ans = IsBitSetTo1(value, data.Item3); + log.InfoFormat("ProcessCmdGet: phy {0} reg {1} value {2} bit {3} ans {4}", item.phyaddress, item.register, value, data.Item3, ans); + return ans; + } + + throw new Exception("no prior config - setdefault should have created this"); + } + + public class example23_switch : Plugin.Plugin + { + public override string Name => "CubeLan 8 port Switch"; + public override string Version => "0.1"; + public override string Author => "Michael Oborne"; + + + public override bool Init() + { + return true; + } + + public override bool Loaded() + { + // Register the ConfigPayload view on the Config tab + SoftwareConfig.AddPluginViewPage(typeof(ConfigSwitch), Name, SoftwareConfig.pageOptions.isConnected); + + return true; + } + + public override bool Exit() { return true; } + } + } +} \ No newline at end of file diff --git a/Plugins/example23-switch.resx b/Plugins/example23-switch.resx new file mode 100644 index 0000000000..1af7de150c --- /dev/null +++ b/Plugins/example23-switch.resx @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=4.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file