diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 3ebd1006a7..b1e4e3f434 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -376,6 +376,12 @@ Component + + UserControl + + + ModifyandSet.cs + UserControl @@ -635,7 +641,6 @@ Simulation.cs - Form @@ -728,6 +733,9 @@ RangeControl.cs + + ModifyandSet.cs + ValuesControl.cs diff --git a/Tools/ArdupilotMegaPlanner/ChangeLog.txt b/Tools/ArdupilotMegaPlanner/ChangeLog.txt index 78f5a44e04..1c3bc78694 100644 --- a/Tools/ArdupilotMegaPlanner/ChangeLog.txt +++ b/Tools/ArdupilotMegaPlanner/ChangeLog.txt @@ -1,9 +1,51 @@ -* Mission Planner 1.2.8 +* Mission Planner 1.2.12 +add arduino chip detect +fix apm2,2.5 dialog test +add write timeout. this will stop planner hangs on bad serial devices. +change quickview decimal places to 0.00 +fix map clicking issue. +fix wind direction wrapping +add airspeed use +modify firmware screen from Marooned +major flightdata tab change. +add save/load polygon from file +add some error handling dialogs + + +* Mission Planner 1.2.11 +Fix ac crosstrack display +tweak ap_mount +speed up Terminal + + +* Mission Planner 1.2.10 +add useritems to HUD +change hdop scale +fix posible follow me bug (, vs .) +fix posible friendly params bug (, vs .) +tweak flightdata log playback timming +fix gridv2 bug. if no waypoint had been done, the grid wold fail +tweak some mission upload potential issues +add ability to get param list from a log (from startup) +add ability to get the first wp list in a log, if wps where received in that log. +tweak video capture library timing + + +* Mission Planner 1.2.9 +add est distance traveled +add est flight time +AP_Mount now updated +add expermental firmware options. +fix hud avi record framerate +add 2 direction wp circle +tweak gridv2 + + +* Mission Planner 1.2.8 fix mjpeg stream from VLC. add grid mode V2 fix hdop scaling - * Mission Planner 1.2.7 add wind from ap add wp every x m in grid mode @@ -11,6 +53,7 @@ fix hil problem fix control-s update mavlink format + * Mission Planner 1.2.6 add tracker location option. fix current sensor screen @@ -18,6 +61,7 @@ add more right click flight planner options. make some connecting error messages more detailed. add partial microdrones protocol output + * Mission Planner 1.2.5 add experimental antenna tracker find add new apparam eeprom reader @@ -29,6 +73,7 @@ move some functions to the right click menu add xplanes data in/out setup to be automatic. add better mission upload handeling. + * Mission Planner 1.2.4 remove geofence tab add guided alt remeber diff --git a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs index 76b2dcccf9..31dced5216 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/HUD.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs @@ -159,7 +159,9 @@ namespace ArdupilotMega.Controls public float groundalt { get; set; } [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public int status { get; set; } + public bool status { get; set; } + bool statuslast = false; + DateTime armedtimer = DateTime.MinValue; public struct Custom { @@ -172,8 +174,7 @@ namespace ArdupilotMega.Controls public Hashtable CustomItems = new Hashtable(); - int statuslast = 0; - DateTime armedtimer = DateTime.MinValue; + public bool bgon = true; public bool hudon = true; @@ -852,7 +853,7 @@ namespace ArdupilotMega.Controls armedtimer = DateTime.Now; } - if (status == 3) // not armed + if (status == false) // not armed { //if ((armedtimer.AddSeconds(8) > DateTime.Now)) { @@ -860,7 +861,7 @@ namespace ArdupilotMega.Controls statuslast = status; } } - else if (status == 4) // armed + else if (status == true) // armed { if ((armedtimer.AddSeconds(8) > DateTime.Now)) { diff --git a/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.Designer.cs new file mode 100644 index 0000000000..73fe322d84 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.Designer.cs @@ -0,0 +1,95 @@ +namespace ArdupilotMega.Controls +{ + partial class ModifyandSet + { + /// + /// 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); + } + + #region Component Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + this.numericUpDown1 = new System.Windows.Forms.NumericUpDown(); + this.myButton1 = new ArdupilotMega.Controls.MyButton(); + this.flowLayoutPanel1 = new System.Windows.Forms.FlowLayoutPanel(); + ((System.ComponentModel.ISupportInitialize)(this.numericUpDown1)).BeginInit(); + this.flowLayoutPanel1.SuspendLayout(); + this.SuspendLayout(); + // + // numericUpDown1 + // + this.numericUpDown1.Location = new System.Drawing.Point(3, 3); + this.numericUpDown1.Maximum = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.numericUpDown1.Name = "numericUpDown1"; + this.numericUpDown1.Size = new System.Drawing.Size(47, 20); + this.numericUpDown1.TabIndex = 0; + this.numericUpDown1.Value = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.numericUpDown1.ValueChanged += new System.EventHandler(this.numericUpDown1_ValueChanged); + // + // myButton1 + // + this.myButton1.Location = new System.Drawing.Point(56, 3); + this.myButton1.Name = "myButton1"; + this.myButton1.Size = new System.Drawing.Size(52, 23); + this.myButton1.TabIndex = 1; + this.myButton1.Text = "Set to This"; + this.myButton1.UseVisualStyleBackColor = true; + this.myButton1.Click += new System.EventHandler(this.myButton1_Click); + // + // flowLayoutPanel1 + // + this.flowLayoutPanel1.Controls.Add(this.numericUpDown1); + this.flowLayoutPanel1.Controls.Add(this.myButton1); + this.flowLayoutPanel1.Dock = System.Windows.Forms.DockStyle.Fill; + this.flowLayoutPanel1.Location = new System.Drawing.Point(0, 0); + this.flowLayoutPanel1.Name = "flowLayoutPanel1"; + this.flowLayoutPanel1.Size = new System.Drawing.Size(114, 29); + this.flowLayoutPanel1.TabIndex = 2; + // + // ModifyandSet + // + this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.flowLayoutPanel1); + this.Name = "ModifyandSet"; + this.Size = new System.Drawing.Size(114, 29); + ((System.ComponentModel.ISupportInitialize)(this.numericUpDown1)).EndInit(); + this.flowLayoutPanel1.ResumeLayout(false); + this.ResumeLayout(false); + + } + + #endregion + + private System.Windows.Forms.NumericUpDown numericUpDown1; + private MyButton myButton1; + private System.Windows.Forms.FlowLayoutPanel flowLayoutPanel1; + } +} diff --git a/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.cs b/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.cs new file mode 100644 index 0000000000..81f1b56a08 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.cs @@ -0,0 +1,47 @@ +using System; +using System.Collections.Generic; +using System.ComponentModel; +using System.Drawing; +using System.Data; +using System.Linq; +using System.Text; +using System.Windows.Forms; + +namespace ArdupilotMega.Controls +{ + public partial class ModifyandSet : UserControl + { + [System.ComponentModel.Browsable(true)] + public NumericUpDown NumericUpDown { get; set; } + [System.ComponentModel.Browsable(true)] + public MyButton Button { get; set; } + + [System.ComponentModel.Browsable(true)] + public String ButtonText { get { return Button.Text; } set { Button.Text = value; } } + [System.ComponentModel.Browsable(true)] + public Decimal Value { get { return NumericUpDown.Value; } set { NumericUpDown.Value = value; } } + + public new event EventHandler Click; + public event EventHandler ValueChanged; + + public ModifyandSet() + { + InitializeComponent(); + + NumericUpDown = numericUpDown1; + Button = myButton1; + } + + private void myButton1_Click(object sender, EventArgs e) + { + if (Click != null) + Click(sender, e); + } + + private void numericUpDown1_ValueChanged(object sender, EventArgs e) + { + if (ValueChanged != null) + ValueChanged(sender, e); + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.resx b/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.resx new file mode 100644 index 0000000000..7080a7d118 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Controls/ModifyandSet.resx @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs b/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs index 4c85bb4259..b4c9ac3e04 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs @@ -12,7 +12,7 @@ using System.Drawing.Drawing2D; namespace ArdupilotMega.Controls { - class MyButton : Button + public class MyButton : Button { bool mouseover = false; bool mousedown = false; diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 391a30e293..5cad04db5c 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -217,8 +217,6 @@ namespace ArdupilotMega PointLatLngAlt _trackerloc = new PointLatLngAlt(); internal PointLatLngAlt TrackerLocation { get { if (_trackerloc.Lng != 0) return _trackerloc; return HomeLocation; } set { _trackerloc = value; } } - internal PointLatLngAlt GuidedModeWP = new PointLatLngAlt(); - public float DistToMAV { get @@ -279,7 +277,7 @@ namespace ArdupilotMega public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane; public float freemem { get; set; } public float brklevel { get; set; } - public int armed { get; set; } + public bool armed { get; set; } // 3dr radio public float rssi { get; set; } @@ -494,7 +492,7 @@ namespace ArdupilotMega { var hb = bytearray.ByteArrayToStructure(6); - armed = (hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED) == (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED ? 4 : 3; + armed = (hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED) == (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED; string oldmode = mode; @@ -764,7 +762,6 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null; } -#if MAVLINK10 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT]; if (bytearray != null) { @@ -789,28 +786,6 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null; } -#else - - bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW]; - if (bytearray != null) - { - var gps = bytearray.ByteArrayToStructure(6); - - lat = gps.lat; - lng = gps.lon; - // alt = gps.alt; // using vfr as includes baro calc - - gpsstatus = gps.fix_type; - // Console.WriteLine("gpsfix {0}",gpsstatus); - - gpshdop = gps.eph; - - groundspeed = gps.v; - groundcourse = gps.hdg; - - //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null; - } -#endif bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS]; if (bytearray != null) @@ -845,7 +820,7 @@ namespace ArdupilotMega lat = loc.lat / 10000000.0f; lng = loc.lon / 10000000.0f; } -#if MAVLINK10 + bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT]; if (bytearray != null) { @@ -862,36 +837,6 @@ namespace ArdupilotMega //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null; } -#else - - bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION]; - if (bytearray != null) - { - var loc = bytearray.ByteArrayToStructure(6); - alt = loc.alt; - lat = loc.lat; - lng = loc.lon; - } - - bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT]; - if (bytearray != null) - { - var wpcur = bytearray.ByteArrayToStructure(6); - - int oldwp = (int)wpno; - - wpno = wpcur.seq; - - if (oldwp != wpno && MainV2.speechEnable && MainV2.speechEngine != null && MainV2.getConfig("speechwaypointenabled") == "True") - { - MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint"))); - } - - //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null; - } - -#endif - bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT]; diff --git a/Tools/ArdupilotMegaPlanner/FollowMe.cs b/Tools/ArdupilotMegaPlanner/FollowMe.cs index f8f257ae8d..b68d62989b 100644 --- a/Tools/ArdupilotMegaPlanner/FollowMe.cs +++ b/Tools/ArdupilotMegaPlanner/FollowMe.cs @@ -162,8 +162,6 @@ namespace ArdupilotMega MainV2.comPort.setGuidedModeWP(gotohere); - MainV2.cs.GuidedModeWP = new PointLatLngAlt(gotohere); - MainV2.giveComport = false; } catch { MainV2.giveComport = false; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs index ca8aa746cf..1f0a7b85e9 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs @@ -137,7 +137,8 @@ resources.GetString("CMB_batmonsensortype.Items"), resources.GetString("CMB_batmonsensortype.Items1"), resources.GetString("CMB_batmonsensortype.Items2"), - resources.GetString("CMB_batmonsensortype.Items3")}); + resources.GetString("CMB_batmonsensortype.Items3"), + resources.GetString("CMB_batmonsensortype.Items4")}); resources.ApplyResources(this.CMB_batmonsensortype, "CMB_batmonsensortype"); this.CMB_batmonsensortype.Name = "CMB_batmonsensortype"; this.CMB_batmonsensortype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmonsensortype_SelectedIndexChanged); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx index 3f3991e00d..75fa537774 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx @@ -468,6 +468,9 @@ 3: AttoPilot 180A + + 4: 3DR IV Sensor + 160, 68 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs index b57b30a3d1..09a44add69 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.Designer.cs @@ -50,10 +50,19 @@ this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar(); this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar(); this.lbl_currentmode = new System.Windows.Forms.Label(); - this.mavlinkCheckBox1 = new ArdupilotMega.Controls.MavlinkCheckBox(); - this.mavlinkNumericUpDown1 = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkCheckBoxthr_fs = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.mavlinkNumericUpDownthr_fs_value = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.LNK_wiki = new System.Windows.Forms.LinkLabel(); + this.mavlinkCheckBoxgcs_fs = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); + this.mavlinkCheckBoxshort_fs = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.mavlinkCheckBoxlong_fs = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.mavlinkCheckBoxthr_fs_action = new ArdupilotMega.Controls.MavlinkCheckBox(); + this.groupBox1 = new System.Windows.Forms.GroupBox(); + this.label3 = new System.Windows.Forms.Label(); ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownthr_fs_value)).BeginInit(); + this.groupBox1.SuspendLayout(); this.SuspendLayout(); // // currentStateBindingSource @@ -300,31 +309,110 @@ resources.ApplyResources(this.lbl_currentmode, "lbl_currentmode"); this.lbl_currentmode.Name = "lbl_currentmode"; // - // mavlinkCheckBox1 + // mavlinkCheckBoxthr_fs // - resources.ApplyResources(this.mavlinkCheckBox1, "mavlinkCheckBox1"); - this.mavlinkCheckBox1.Name = "mavlinkCheckBox1"; - this.mavlinkCheckBox1.OffValue = 0F; - this.mavlinkCheckBox1.OnValue = 1F; - this.mavlinkCheckBox1.param = null; - this.mavlinkCheckBox1.ParamName = null; - this.mavlinkCheckBox1.UseVisualStyleBackColor = true; + resources.ApplyResources(this.mavlinkCheckBoxthr_fs, "mavlinkCheckBoxthr_fs"); + this.mavlinkCheckBoxthr_fs.Name = "mavlinkCheckBoxthr_fs"; + this.mavlinkCheckBoxthr_fs.OffValue = 0F; + this.mavlinkCheckBoxthr_fs.OnValue = 1F; + this.mavlinkCheckBoxthr_fs.param = null; + this.mavlinkCheckBoxthr_fs.ParamName = null; + this.toolTip1.SetToolTip(this.mavlinkCheckBoxthr_fs, resources.GetString("mavlinkCheckBoxthr_fs.ToolTip")); + this.mavlinkCheckBoxthr_fs.UseVisualStyleBackColor = true; // - // mavlinkNumericUpDown1 + // mavlinkNumericUpDownthr_fs_value // - resources.ApplyResources(this.mavlinkNumericUpDown1, "mavlinkNumericUpDown1"); - this.mavlinkNumericUpDown1.Max = 1F; - this.mavlinkNumericUpDown1.Min = 0F; - this.mavlinkNumericUpDown1.Name = "mavlinkNumericUpDown1"; - this.mavlinkNumericUpDown1.param = null; - this.mavlinkNumericUpDown1.ParamName = null; + resources.ApplyResources(this.mavlinkNumericUpDownthr_fs_value, "mavlinkNumericUpDownthr_fs_value"); + this.mavlinkNumericUpDownthr_fs_value.Max = 1F; + this.mavlinkNumericUpDownthr_fs_value.Min = 0F; + this.mavlinkNumericUpDownthr_fs_value.Name = "mavlinkNumericUpDownthr_fs_value"; + this.mavlinkNumericUpDownthr_fs_value.param = null; + this.mavlinkNumericUpDownthr_fs_value.ParamName = null; + this.toolTip1.SetToolTip(this.mavlinkNumericUpDownthr_fs_value, resources.GetString("mavlinkNumericUpDownthr_fs_value.ToolTip")); + // + // LNK_wiki + // + resources.ApplyResources(this.LNK_wiki, "LNK_wiki"); + this.LNK_wiki.LinkBehavior = System.Windows.Forms.LinkBehavior.HoverUnderline; + this.LNK_wiki.LinkColor = System.Drawing.Color.CornflowerBlue; + this.LNK_wiki.Name = "LNK_wiki"; + this.LNK_wiki.TabStop = true; + this.LNK_wiki.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.LNK_wiki_LinkClicked); + // + // mavlinkCheckBoxgcs_fs + // + resources.ApplyResources(this.mavlinkCheckBoxgcs_fs, "mavlinkCheckBoxgcs_fs"); + this.mavlinkCheckBoxgcs_fs.Name = "mavlinkCheckBoxgcs_fs"; + this.mavlinkCheckBoxgcs_fs.OffValue = 0F; + this.mavlinkCheckBoxgcs_fs.OnValue = 1F; + this.mavlinkCheckBoxgcs_fs.param = null; + this.mavlinkCheckBoxgcs_fs.ParamName = null; + this.toolTip1.SetToolTip(this.mavlinkCheckBoxgcs_fs, resources.GetString("mavlinkCheckBoxgcs_fs.ToolTip")); + this.mavlinkCheckBoxgcs_fs.UseVisualStyleBackColor = true; + // + // toolTip1 + // + this.toolTip1.AutoPopDelay = 20000; + this.toolTip1.InitialDelay = 500; + this.toolTip1.ReshowDelay = 100; + // + // mavlinkCheckBoxshort_fs + // + resources.ApplyResources(this.mavlinkCheckBoxshort_fs, "mavlinkCheckBoxshort_fs"); + this.mavlinkCheckBoxshort_fs.Name = "mavlinkCheckBoxshort_fs"; + this.mavlinkCheckBoxshort_fs.OffValue = 0F; + this.mavlinkCheckBoxshort_fs.OnValue = 1F; + this.mavlinkCheckBoxshort_fs.param = null; + this.mavlinkCheckBoxshort_fs.ParamName = null; + this.toolTip1.SetToolTip(this.mavlinkCheckBoxshort_fs, resources.GetString("mavlinkCheckBoxshort_fs.ToolTip")); + this.mavlinkCheckBoxshort_fs.UseVisualStyleBackColor = true; + // + // mavlinkCheckBoxlong_fs + // + resources.ApplyResources(this.mavlinkCheckBoxlong_fs, "mavlinkCheckBoxlong_fs"); + this.mavlinkCheckBoxlong_fs.Name = "mavlinkCheckBoxlong_fs"; + this.mavlinkCheckBoxlong_fs.OffValue = 0F; + this.mavlinkCheckBoxlong_fs.OnValue = 1F; + this.mavlinkCheckBoxlong_fs.param = null; + this.mavlinkCheckBoxlong_fs.ParamName = null; + this.toolTip1.SetToolTip(this.mavlinkCheckBoxlong_fs, resources.GetString("mavlinkCheckBoxlong_fs.ToolTip")); + this.mavlinkCheckBoxlong_fs.UseVisualStyleBackColor = true; + // + // mavlinkCheckBoxthr_fs_action + // + resources.ApplyResources(this.mavlinkCheckBoxthr_fs_action, "mavlinkCheckBoxthr_fs_action"); + this.mavlinkCheckBoxthr_fs_action.Name = "mavlinkCheckBoxthr_fs_action"; + this.mavlinkCheckBoxthr_fs_action.OffValue = 0F; + this.mavlinkCheckBoxthr_fs_action.OnValue = 1F; + this.mavlinkCheckBoxthr_fs_action.param = null; + this.mavlinkCheckBoxthr_fs_action.ParamName = null; + this.toolTip1.SetToolTip(this.mavlinkCheckBoxthr_fs_action, resources.GetString("mavlinkCheckBoxthr_fs_action.ToolTip")); + this.mavlinkCheckBoxthr_fs_action.UseVisualStyleBackColor = true; + // + // groupBox1 + // + this.groupBox1.Controls.Add(this.label3); + this.groupBox1.Controls.Add(this.mavlinkCheckBoxthr_fs); + this.groupBox1.Controls.Add(this.mavlinkCheckBoxthr_fs_action); + this.groupBox1.Controls.Add(this.mavlinkNumericUpDownthr_fs_value); + this.groupBox1.Controls.Add(this.mavlinkCheckBoxlong_fs); + this.groupBox1.Controls.Add(this.mavlinkCheckBoxgcs_fs); + this.groupBox1.Controls.Add(this.mavlinkCheckBoxshort_fs); + resources.ApplyResources(this.groupBox1, "groupBox1"); + this.groupBox1.Name = "groupBox1"; + this.groupBox1.TabStop = false; + // + // label3 + // + resources.ApplyResources(this.label3, "label3"); + this.label3.Name = "label3"; // // ConfigFailSafe // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.Controls.Add(this.mavlinkNumericUpDown1); - this.Controls.Add(this.mavlinkCheckBox1); + this.Controls.Add(this.groupBox1); + this.Controls.Add(this.LNK_wiki); this.Controls.Add(this.lbl_currentmode); this.Controls.Add(this.label2); this.Controls.Add(this.label1); @@ -346,7 +434,9 @@ this.Controls.Add(this.horizontalProgressBar1); this.Name = "ConfigFailSafe"; ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownthr_fs_value)).EndInit(); + this.groupBox1.ResumeLayout(false); + this.groupBox1.PerformLayout(); this.ResumeLayout(false); this.PerformLayout(); @@ -374,7 +464,15 @@ private HorizontalProgressBar horizontalProgressBar2; private HorizontalProgressBar horizontalProgressBar1; private System.Windows.Forms.Label lbl_currentmode; - private Controls.MavlinkCheckBox mavlinkCheckBox1; - private Controls.MavlinkNumericUpDown mavlinkNumericUpDown1; + private Controls.MavlinkCheckBox mavlinkCheckBoxthr_fs; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDownthr_fs_value; + private System.Windows.Forms.LinkLabel LNK_wiki; + private Controls.MavlinkCheckBox mavlinkCheckBoxgcs_fs; + private System.Windows.Forms.ToolTip toolTip1; + private Controls.MavlinkCheckBox mavlinkCheckBoxshort_fs; + private Controls.MavlinkCheckBox mavlinkCheckBoxlong_fs; + private Controls.MavlinkCheckBox mavlinkCheckBoxthr_fs_action; + private System.Windows.Forms.GroupBox groupBox1; + private System.Windows.Forms.Label label3; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs index 198b515600..696f20277b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.cs @@ -8,20 +8,19 @@ using System.Text; using System.Windows.Forms; using ArdupilotMega.Controls.BackstageView; using ArdupilotMega.Controls; +using System.Diagnostics; namespace ArdupilotMega.GCSViews.ConfigurationView { public partial class ConfigFailSafe : UserControl, IActivate, IDeactivate { Timer timer = new Timer(); + // public ConfigFailSafe() { InitializeComponent(); - mavlinkCheckBox1.setup(1, 0, "THR_FAILSAFE", MainV2.comPort.param); - mavlinkNumericUpDown1.setup(800, 1200, 1, 1, "THR_FS_VALUE", MainV2.comPort.param); - // setup rc update timer.Tick += new EventHandler(timer_Tick); } @@ -43,11 +42,23 @@ namespace ArdupilotMega.GCSViews.ConfigurationView public void Activate() { + mavlinkCheckBoxthr_fs.setup(1, 0, "THR_FAILSAFE", MainV2.comPort.param, mavlinkNumericUpDownthr_fs_value); + mavlinkNumericUpDownthr_fs_value.setup(800, 1200, 1, 1, "THR_FS_VALUE", MainV2.comPort.param); + mavlinkCheckBoxthr_fs_action.setup(1, 0, "THR_FS_ACTION",MainV2.comPort.param); + mavlinkCheckBoxgcs_fs.setup(1, 0, "FS_GCS_ENABL", MainV2.comPort.param); + mavlinkCheckBoxshort_fs.setup(1, 0, "FS_SHORT_ACTN", MainV2.comPort.param); + mavlinkCheckBoxlong_fs.setup(1, 0, "FS_LONG_ACTN", MainV2.comPort.param); + timer.Enabled = true; timer.Interval = 100; timer.Start(); CustomMessageBox.Show("Ensure your props are not on the Plane/Quad","FailSafe",MessageBoxButtons.OK,MessageBoxIcon.Exclamation); } + + private void LNK_wiki_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e) + { + Process.Start(new ProcessStartInfo("http://code.google.com/p/ardupilot-mega/wiki/APM2xFailsafe")); + } } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx index 04ea0521d6..023e0d1783 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFailSafe.resx @@ -199,7 +199,7 @@ horizontalProgressBar9 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -223,7 +223,7 @@ horizontalProgressBar10 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -247,7 +247,7 @@ horizontalProgressBar11 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -271,7 +271,7 @@ horizontalProgressBar12 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -295,7 +295,7 @@ horizontalProgressBar13 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -319,7 +319,7 @@ horizontalProgressBar14 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -343,7 +343,7 @@ horizontalProgressBar15 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -367,7 +367,7 @@ horizontalProgressBar16 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -391,7 +391,7 @@ horizontalProgressBar8 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -415,7 +415,7 @@ horizontalProgressBar7 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -439,7 +439,7 @@ horizontalProgressBar6 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -463,7 +463,7 @@ horizontalProgressBar5 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -487,7 +487,7 @@ horizontalProgressBar4 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -511,7 +511,7 @@ horizontalProgressBar3 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -535,7 +535,7 @@ horizontalProgressBar2 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -559,7 +559,7 @@ horizontalProgressBar1 - ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null $this @@ -577,7 +577,7 @@ 473, 21 - 275, 50 + 215, 50 140 @@ -600,58 +600,293 @@ 2 - + True - + False - - 556, 94 + + 6, 19 - + 103, 17 - + 141 - + Throttle FailSafe - - mavlinkCheckBox1 + + 214, 17 + + + Enable Failsafe on low throttle pwm - - ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + mavlinkCheckBoxthr_fs - - $this + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null - + + groupBox1 + + 1 - + False - - 556, 118 + + 42, 42 - - 120, 20 + + 103, 20 - + 142 - - mavlinkNumericUpDown1 + + Trigger Throttle Pwm - - ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4640.13049, Culture=neutral, PublicKeyToken=null + + mavlinkNumericUpDownthr_fs_value - + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 3 + + + Top, Right + + + True + + + 657, 5 + + + 28, 13 + + + 143 + + + Wiki + + + LNK_wiki + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + $this - + + 1 + + + True + + + False + + + NoControl + + + 6, 92 + + + 89, 17 + + + 144 + + + GCS FailSafe + + + Enable Failsafe on GCS loss of communication + + + mavlinkCheckBoxgcs_fs + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 5 + + + True + + + False + + + NoControl + + + 6, 115 + + + 127, 17 + + + 145 + + + FailSafe Short (1 sec) + + + Off, no Action, On, RTL + + + mavlinkCheckBoxshort_fs + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 6 + + + True + + + False + + + NoControl + + + 6, 138 + + + 132, 17 + + + 146 + + + FailSafe Long (20 sec) + + + Off, no Action, On, RTL + + + mavlinkCheckBoxlong_fs + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 4 + + + True + + + False + + + NoControl + + + 6, 69 + + + 134, 17 + + + 147 + + + Throttle Failsafe Action + + + Arducopter Auto: Off, no Action, On, RTL +Arducopter Other: if have gps, RTL, Otherwise Land + + + mavlinkCheckBoxthr_fs_action + + + ArdupilotMega.Controls.MavlinkCheckBox, ArdupilotMegaPlanner10, Version=1.1.4646.37607, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 2 + + + True + + + 6, 48 + + + 30, 13 + + + 148 + + + Pwm + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 0 + + + 495, 76 + + + 170, 167 + + + 148 + + + FailSafe Options + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + 0 @@ -661,7 +896,7 @@ 6, 13 - 751, 478 + 688, 448 currentStateBindingSource @@ -669,6 +904,12 @@ System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + toolTip1 + + + System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + ConfigFailSafe diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs index f66f78a940..8dc7a4fa71 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs @@ -83,7 +83,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1"; CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1"; } - catch (Exception ex) { /*CustomMessageBox.Show("Missing RC rev Param " + ex.ToString());*/ } + catch {}//(Exception ex) { CustomMessageBox.Show("Missing RC rev Param " + ex.ToString()); } startup = false; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs index 21aab51f67..1568a147be 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs @@ -140,6 +140,12 @@ resources.ApplyResources(this.RawValue, "RawValue"); this.RawValue.Name = "RawValue"; // + // toolTip1 + // + this.toolTip1.AutoPopDelay = 20000; + this.toolTip1.InitialDelay = 500; + this.toolTip1.ReshowDelay = 100; + // // ConfigRawParams // resources.ApplyResources(this, "$this"); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx index e4bef97a51..761c28a830 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx @@ -142,7 +142,7 @@ BUT_compare - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.35335, Culture=neutral, PublicKeyToken=null $this @@ -172,7 +172,7 @@ BUT_rerequestparams - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.35335, Culture=neutral, PublicKeyToken=null $this @@ -202,7 +202,7 @@ BUT_writePIDS - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.35335, Culture=neutral, PublicKeyToken=null $this @@ -235,7 +235,7 @@ BUT_save - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.35335, Culture=neutral, PublicKeyToken=null $this @@ -268,7 +268,7 @@ BUT_load - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.35335, Culture=neutral, PublicKeyToken=null $this @@ -397,6 +397,6 @@ ConfigRawParams - ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs index ed9e82af79..7258ab4365 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs @@ -33,14 +33,12 @@ this.groupBox5 = new System.Windows.Forms.GroupBox(); this.H_SWASH_TYPE = new System.Windows.Forms.RadioButton(); this.CCPM = new System.Windows.Forms.RadioButton(); - this.BUT_swash_manual = new ArdupilotMega.Controls.MyButton(); this.label41 = new System.Windows.Forms.Label(); this.groupBox3 = new System.Windows.Forms.GroupBox(); this.label46 = new System.Windows.Forms.Label(); this.label45 = new System.Windows.Forms.Label(); this.H_GYR_ENABLE = new System.Windows.Forms.CheckBox(); this.H_GYR_GAIN = new System.Windows.Forms.TextBox(); - this.BUT_HS4save = new ArdupilotMega.Controls.MyButton(); this.label21 = new System.Windows.Forms.Label(); this.H_COL_MIN = new System.Windows.Forms.TextBox(); this.groupBox1 = new System.Windows.Forms.GroupBox(); @@ -60,9 +58,7 @@ this.label37 = new System.Windows.Forms.Label(); this.label36 = new System.Windows.Forms.Label(); this.label26 = new System.Windows.Forms.Label(); - this.H_PIT_MAX = new System.Windows.Forms.TextBox(); this.label25 = new System.Windows.Forms.Label(); - this.H_ROL_MAX = new System.Windows.Forms.TextBox(); this.label23 = new System.Windows.Forms.Label(); this.label22 = new System.Windows.Forms.Label(); this.label20 = new System.Windows.Forms.Label(); @@ -75,15 +71,27 @@ this.HS2_REV = new System.Windows.Forms.CheckBox(); this.HS1_REV = new System.Windows.Forms.CheckBox(); this.label17 = new System.Windows.Forms.Label(); - this.HS4 = new ArdupilotMega.HorizontalProgressBar2(); - this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); - this.HS3 = new ArdupilotMega.VerticalProgressBar2(); - this.Gservoloc = new AGaugeApp.AGauge(); this.label44 = new System.Windows.Forms.Label(); this.label43 = new System.Windows.Forms.Label(); this.label42 = new System.Windows.Forms.Label(); this.HS4_TRIM = new System.Windows.Forms.NumericUpDown(); this.HS4_REV = new System.Windows.Forms.CheckBox(); + this.label1 = new System.Windows.Forms.Label(); + this.label2 = new System.Windows.Forms.Label(); + this.mavlinkNumericUpDown3max = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkNumericUpDown3min = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkNumericUpDown2max = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkNumericUpDown2min = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkNumericUpDown1max = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkNumericUpDown1min = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.BUT_swash_manual = new ArdupilotMega.Controls.MyButton(); + this.BUT_HS4save = new ArdupilotMega.Controls.MyButton(); + this.HS4 = new ArdupilotMega.HorizontalProgressBar2(); + this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components); + this.HS3 = new ArdupilotMega.VerticalProgressBar2(); + this.Gservoloc = new AGaugeApp.AGauge(); + this.mavlinkNumericUpDownrollmax = new ArdupilotMega.Controls.MavlinkNumericUpDown(); + this.mavlinkNumericUpDownpitchmax = new ArdupilotMega.Controls.MavlinkNumericUpDown(); this.groupBox5.SuspendLayout(); this.groupBox3.SuspendLayout(); this.groupBox1.SuspendLayout(); @@ -91,8 +99,16 @@ ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit(); - ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown3max)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown3min)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown2max)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown2min)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1max)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1min)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownrollmax)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownpitchmax)).BeginInit(); this.SuspendLayout(); // // groupBox5 @@ -118,13 +134,6 @@ this.CCPM.TabStop = true; this.CCPM.UseVisualStyleBackColor = true; // - // BUT_swash_manual - // - resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual"); - this.BUT_swash_manual.Name = "BUT_swash_manual"; - this.BUT_swash_manual.UseVisualStyleBackColor = true; - this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click); - // // label41 // resources.ApplyResources(this.label41, "label41"); @@ -163,13 +172,6 @@ this.H_GYR_GAIN.Name = "H_GYR_GAIN"; this.H_GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating); // - // BUT_HS4save - // - resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save"); - this.BUT_HS4save.Name = "BUT_HS4save"; - this.BUT_HS4save.UseVisualStyleBackColor = true; - this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click); - // // label21 // resources.ApplyResources(this.label21, "label21"); @@ -335,23 +337,11 @@ resources.ApplyResources(this.label26, "label26"); this.label26.Name = "label26"; // - // H_PIT_MAX - // - resources.ApplyResources(this.H_PIT_MAX, "H_PIT_MAX"); - this.H_PIT_MAX.Name = "H_PIT_MAX"; - this.H_PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating); - // // label25 // resources.ApplyResources(this.label25, "label25"); this.label25.Name = "label25"; // - // H_ROL_MAX - // - resources.ApplyResources(this.H_ROL_MAX, "H_ROL_MAX"); - this.H_ROL_MAX.Name = "H_ROL_MAX"; - this.H_ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating); - // // label23 // resources.ApplyResources(this.label23, "label23"); @@ -421,6 +411,127 @@ resources.ApplyResources(this.label17, "label17"); this.label17.Name = "label17"; // + // label44 + // + resources.ApplyResources(this.label44, "label44"); + this.label44.Name = "label44"; + // + // label43 + // + resources.ApplyResources(this.label43, "label43"); + this.label43.Name = "label43"; + // + // label42 + // + resources.ApplyResources(this.label42, "label42"); + this.label42.Name = "label42"; + // + // HS4_TRIM + // + resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM"); + this.HS4_TRIM.Maximum = new decimal(new int[] { + 2000, + 0, + 0, + 0}); + this.HS4_TRIM.Minimum = new decimal(new int[] { + 1000, + 0, + 0, + 0}); + this.HS4_TRIM.Name = "HS4_TRIM"; + this.HS4_TRIM.Value = new decimal(new int[] { + 1500, + 0, + 0, + 0}); + this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged); + // + // HS4_REV + // + resources.ApplyResources(this.HS4_REV, "HS4_REV"); + this.HS4_REV.Name = "HS4_REV"; + this.HS4_REV.UseVisualStyleBackColor = true; + this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged); + // + // label1 + // + resources.ApplyResources(this.label1, "label1"); + this.label1.Name = "label1"; + // + // label2 + // + resources.ApplyResources(this.label2, "label2"); + this.label2.Name = "label2"; + // + // mavlinkNumericUpDown3max + // + resources.ApplyResources(this.mavlinkNumericUpDown3max, "mavlinkNumericUpDown3max"); + this.mavlinkNumericUpDown3max.Max = 1F; + this.mavlinkNumericUpDown3max.Min = 0F; + this.mavlinkNumericUpDown3max.Name = "mavlinkNumericUpDown3max"; + this.mavlinkNumericUpDown3max.param = null; + this.mavlinkNumericUpDown3max.ParamName = null; + // + // mavlinkNumericUpDown3min + // + resources.ApplyResources(this.mavlinkNumericUpDown3min, "mavlinkNumericUpDown3min"); + this.mavlinkNumericUpDown3min.Max = 1F; + this.mavlinkNumericUpDown3min.Min = 0F; + this.mavlinkNumericUpDown3min.Name = "mavlinkNumericUpDown3min"; + this.mavlinkNumericUpDown3min.param = null; + this.mavlinkNumericUpDown3min.ParamName = null; + // + // mavlinkNumericUpDown2max + // + resources.ApplyResources(this.mavlinkNumericUpDown2max, "mavlinkNumericUpDown2max"); + this.mavlinkNumericUpDown2max.Max = 1F; + this.mavlinkNumericUpDown2max.Min = 0F; + this.mavlinkNumericUpDown2max.Name = "mavlinkNumericUpDown2max"; + this.mavlinkNumericUpDown2max.param = null; + this.mavlinkNumericUpDown2max.ParamName = null; + // + // mavlinkNumericUpDown2min + // + resources.ApplyResources(this.mavlinkNumericUpDown2min, "mavlinkNumericUpDown2min"); + this.mavlinkNumericUpDown2min.Max = 1F; + this.mavlinkNumericUpDown2min.Min = 0F; + this.mavlinkNumericUpDown2min.Name = "mavlinkNumericUpDown2min"; + this.mavlinkNumericUpDown2min.param = null; + this.mavlinkNumericUpDown2min.ParamName = null; + // + // mavlinkNumericUpDown1max + // + resources.ApplyResources(this.mavlinkNumericUpDown1max, "mavlinkNumericUpDown1max"); + this.mavlinkNumericUpDown1max.Max = 1F; + this.mavlinkNumericUpDown1max.Min = 0F; + this.mavlinkNumericUpDown1max.Name = "mavlinkNumericUpDown1max"; + this.mavlinkNumericUpDown1max.param = null; + this.mavlinkNumericUpDown1max.ParamName = null; + // + // mavlinkNumericUpDown1min + // + resources.ApplyResources(this.mavlinkNumericUpDown1min, "mavlinkNumericUpDown1min"); + this.mavlinkNumericUpDown1min.Max = 1F; + this.mavlinkNumericUpDown1min.Min = 0F; + this.mavlinkNumericUpDown1min.Name = "mavlinkNumericUpDown1min"; + this.mavlinkNumericUpDown1min.param = null; + this.mavlinkNumericUpDown1min.ParamName = null; + // + // BUT_swash_manual + // + resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual"); + this.BUT_swash_manual.Name = "BUT_swash_manual"; + this.BUT_swash_manual.UseVisualStyleBackColor = true; + this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click); + // + // BUT_HS4save + // + resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save"); + this.BUT_HS4save.Name = "BUT_HS4save"; + this.BUT_HS4save.UseVisualStyleBackColor = true; + this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click); + // // HS4 // this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69))))); @@ -600,53 +711,38 @@ this.Gservoloc.Value2 = 180F; this.Gservoloc.Value3 = 0F; // - // label44 + // mavlinkNumericUpDownrollmax // - resources.ApplyResources(this.label44, "label44"); - this.label44.Name = "label44"; + resources.ApplyResources(this.mavlinkNumericUpDownrollmax, "mavlinkNumericUpDownrollmax"); + this.mavlinkNumericUpDownrollmax.Max = 1F; + this.mavlinkNumericUpDownrollmax.Min = 0F; + this.mavlinkNumericUpDownrollmax.Name = "mavlinkNumericUpDownrollmax"; + this.mavlinkNumericUpDownrollmax.param = null; + this.mavlinkNumericUpDownrollmax.ParamName = null; // - // label43 + // mavlinkNumericUpDownpitchmax // - resources.ApplyResources(this.label43, "label43"); - this.label43.Name = "label43"; - // - // label42 - // - resources.ApplyResources(this.label42, "label42"); - this.label42.Name = "label42"; - // - // HS4_TRIM - // - resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM"); - this.HS4_TRIM.Maximum = new decimal(new int[] { - 2000, - 0, - 0, - 0}); - this.HS4_TRIM.Minimum = new decimal(new int[] { - 1000, - 0, - 0, - 0}); - this.HS4_TRIM.Name = "HS4_TRIM"; - this.HS4_TRIM.Value = new decimal(new int[] { - 1500, - 0, - 0, - 0}); - this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged); - // - // HS4_REV - // - resources.ApplyResources(this.HS4_REV, "HS4_REV"); - this.HS4_REV.Name = "HS4_REV"; - this.HS4_REV.UseVisualStyleBackColor = true; - this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged); + resources.ApplyResources(this.mavlinkNumericUpDownpitchmax, "mavlinkNumericUpDownpitchmax"); + this.mavlinkNumericUpDownpitchmax.Max = 1F; + this.mavlinkNumericUpDownpitchmax.Min = 0F; + this.mavlinkNumericUpDownpitchmax.Name = "mavlinkNumericUpDownpitchmax"; + this.mavlinkNumericUpDownpitchmax.param = null; + this.mavlinkNumericUpDownpitchmax.ParamName = null; // // ConfigTradHeli // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.mavlinkNumericUpDownpitchmax); + this.Controls.Add(this.mavlinkNumericUpDownrollmax); + this.Controls.Add(this.label2); + this.Controls.Add(this.label1); + this.Controls.Add(this.mavlinkNumericUpDown3max); + this.Controls.Add(this.mavlinkNumericUpDown3min); + this.Controls.Add(this.mavlinkNumericUpDown2max); + this.Controls.Add(this.mavlinkNumericUpDown2min); + this.Controls.Add(this.mavlinkNumericUpDown1max); + this.Controls.Add(this.mavlinkNumericUpDown1min); this.Controls.Add(this.label44); this.Controls.Add(this.label43); this.Controls.Add(this.label42); @@ -666,9 +762,7 @@ this.Controls.Add(this.label37); this.Controls.Add(this.label36); this.Controls.Add(this.label26); - this.Controls.Add(this.H_PIT_MAX); this.Controls.Add(this.label25); - this.Controls.Add(this.H_ROL_MAX); this.Controls.Add(this.label23); this.Controls.Add(this.label22); this.Controls.Add(this.label20); @@ -696,8 +790,16 @@ ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit(); - ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown3max)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown3min)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown2max)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown2min)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1max)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1min)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownrollmax)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownpitchmax)).EndInit(); this.ResumeLayout(false); this.PerformLayout(); @@ -735,9 +837,7 @@ private System.Windows.Forms.Label label37; private System.Windows.Forms.Label label36; private System.Windows.Forms.Label label26; - private System.Windows.Forms.TextBox H_PIT_MAX; private System.Windows.Forms.Label label25; - private System.Windows.Forms.TextBox H_ROL_MAX; private System.Windows.Forms.Label label23; private System.Windows.Forms.Label label22; private System.Windows.Forms.Label label20; @@ -759,5 +859,15 @@ private System.Windows.Forms.Label label42; private System.Windows.Forms.NumericUpDown HS4_TRIM; private System.Windows.Forms.CheckBox HS4_REV; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown1min; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown1max; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown2max; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown2min; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown3max; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDown3min; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.Label label2; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDownrollmax; + private Controls.MavlinkNumericUpDown mavlinkNumericUpDownpitchmax; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs index 1c806247fb..6d8f4f328b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs @@ -383,6 +383,16 @@ namespace ArdupilotMega.GCSViews.ConfigurationView timer.Interval = 100; timer.Start(); + mavlinkNumericUpDown1min.setup(800,1400,1,1,"HS1_MIN",MainV2.comPort.param); + mavlinkNumericUpDown1max.setup(1600,2200,1,1,"HS1_MAX",MainV2.comPort.param); + mavlinkNumericUpDown2min.setup(800, 1400, 1, 1, "HS2_MIN", MainV2.comPort.param); + mavlinkNumericUpDown2max.setup(1600, 2200, 1, 1, "HS2_MAX", MainV2.comPort.param); + mavlinkNumericUpDown3min.setup(800, 1400, 1, 1, "HS3_MIN", MainV2.comPort.param); + mavlinkNumericUpDown3max.setup(1600, 2200, 1, 1, "HS3_MAX", MainV2.comPort.param); + + mavlinkNumericUpDownpitchmax.setup(10, 65, 100, 1, "H_PIT_MAX", MainV2.comPort.param); + mavlinkNumericUpDownrollmax.setup(10, 65, 100, 1, "H_ROL_MAX", MainV2.comPort.param); + startup = true; try { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx index e9031e5c21..dd225743f0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx @@ -117,14 +117,66 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + H_SWASH_TYPE + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 0 + + + CCPM + + + System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox5 + + + 1 + + + 269, 11 + + + 120, 43 + + + + 169 + + + Swash Type + + + groupBox5 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + + NoControl + 67, 15 42, 24 - 0 @@ -146,7 +198,6 @@ True - NoControl @@ -174,57 +225,6 @@ 1 - - 257, 11 - - - 120, 43 - - - 169 - - - Swash Type - - - groupBox5 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 5 - - - NoControl - - - 302, 83 - - - 69, 23 - - - 138 - - - Manual - - - BUT_swash_manual - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null - - - $this - - - 6 - True @@ -255,6 +255,78 @@ 0 + + label46 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 0 + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 1 + + + H_GYR_ENABLE + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 2 + + + H_GYR_GAIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 437, 314 + + + 101, 63 + + + 168 + + + External Gyro + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + True @@ -366,57 +438,6 @@ 3 - - 437, 314 - - - 101, 63 - - - 168 - - - Gyro - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 7 - - - NoControl - - - 483, 174 - - - 69, 23 - - - 167 - - - Manual - - - BUT_HS4save - - - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null - - - $this - - - 8 - True @@ -474,6 +495,63 @@ 2 + + H_COL_MID + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + H_COL_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + BUT_0collective + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + groupBox1 + + + 5 + + + 309, 95 + + + 80, 209 + + + 165 + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + False @@ -550,7 +628,7 @@ BUT_0collective - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null groupBox1 @@ -558,26 +636,74 @@ 5 - - 297, 95 + + label24 - - 80, 209 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 165 + + groupBox2 - - groupBox1 + + 0 - + + HS4_MIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + HS4_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + label40 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 437, 186 + + + 169, 78 + + + 166 + + + groupBox2 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + $this - - 9 + + 20 True @@ -693,29 +819,8 @@ 3 - - 437, 186 - - - 169, 78 - - - 166 - - - groupBox2 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 10 - - 126, 314 + 96, 314 44, 20 @@ -733,10 +838,10 @@ $this - 11 + 21 - 126, 288 + 96, 288 44, 20 @@ -754,10 +859,10 @@ $this - 12 + 22 - 126, 262 + 96, 262 44, 20 @@ -775,7 +880,7 @@ $this - 13 + 23 True @@ -784,7 +889,7 @@ NoControl - 131, 249 + 101, 249 27, 13 @@ -805,7 +910,7 @@ $this - 14 + 24 True @@ -814,7 +919,7 @@ NoControl - 102, 249 + 72, 249 27, 13 @@ -835,7 +940,7 @@ $this - 15 + 25 True @@ -844,7 +949,7 @@ NoControl - 54, 249 + 31, 249 44, 13 @@ -865,7 +970,7 @@ $this - 16 + 26 True @@ -874,7 +979,7 @@ NoControl - 17, 249 + -1, 249 35, 13 @@ -895,7 +1000,7 @@ $this - 17 + 27 True @@ -904,7 +1009,7 @@ NoControl - 260, 365 + 272, 365 54, 13 @@ -925,31 +1030,7 @@ $this - 18 - - - 314, 362 - - - 47, 20 - - - 156 - - - 4500 - - - H_PIT_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 19 + 28 True @@ -958,7 +1039,7 @@ NoControl - 260, 341 + 272, 341 48, 13 @@ -979,31 +1060,7 @@ $this - 20 - - - 314, 336 - - - 47, 20 - - - 154 - - - 4500 - - - H_ROL_MAX - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 21 + 29 True @@ -1033,7 +1090,7 @@ $this - 22 + 30 True @@ -1042,7 +1099,7 @@ NoControl - 236, 66 + 248, 66 72, 13 @@ -1063,7 +1120,7 @@ $this - 23 + 31 True @@ -1072,7 +1129,7 @@ NoControl - 27, 317 + 9, 317 13, 13 @@ -1093,7 +1150,7 @@ $this - 24 + 32 True @@ -1102,7 +1159,7 @@ NoControl - 27, 291 + 9, 291 13, 13 @@ -1123,7 +1180,7 @@ $this - 25 + 33 True @@ -1132,7 +1189,7 @@ NoControl - 27, 265 + 9, 265 13, 13 @@ -1153,13 +1210,13 @@ $this - 26 + 34 - 57, 314 + 34, 314 - 39, 20 + 30, 20 146 @@ -1177,13 +1234,13 @@ $this - 27 + 35 - 57, 288 + 34, 288 - 39, 20 + 30, 20 145 @@ -1201,13 +1258,13 @@ $this - 28 + 36 - 57, 262 + 34, 262 - 39, 20 + 30, 20 144 @@ -1225,7 +1282,7 @@ $this - 29 + 37 True @@ -1234,7 +1291,7 @@ NoControl - 105, 317 + 75, 317 15, 14 @@ -1252,7 +1309,7 @@ $this - 30 + 38 True @@ -1261,7 +1318,7 @@ NoControl - 105, 291 + 75, 291 15, 14 @@ -1279,7 +1336,7 @@ $this - 31 + 39 True @@ -1288,7 +1345,7 @@ NoControl - 105, 268 + 75, 268 15, 14 @@ -1306,7 +1363,7 @@ $this - 32 + 40 True @@ -1336,82 +1393,7 @@ $this - 33 - - - 17, 17 - - - 396, 93 - - - 242, 42 - - - 152 - - - HS4 - - - ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null - - - $this - - - 34 - - - 239, 95 - - - 42, 213 - - - 151 - - - HS3 - - - ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null - - - $this - - - 35 - - - Zoom - - - Microsoft Sans Serif, 9pt - - - 20, 93 - - - 0, 0, 0, 0 - - - 150, 150 - - - 139 - - - Gservoloc - - - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null - - - $this - - - 36 + 41 True @@ -1441,7 +1423,7 @@ $this - 0 + 10 True @@ -1471,7 +1453,7 @@ $this - 1 + 11 True @@ -1501,7 +1483,7 @@ $this - 2 + 12 532, 284 @@ -1522,7 +1504,7 @@ $this - 3 + 13 True @@ -1549,8 +1531,392 @@ $this + 14 + + + True + + + NoControl + + + 152, 249 + + + 24, 13 + + + 181 + + + Min + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + True + + + NoControl + + + 203, 249 + + + 27, 13 + + + 182 + + + Max + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + False + + + 197, 314 + + + 44, 20 + + + 180 + + + mavlinkNumericUpDown3max + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + 4 + + False + + + 146, 314 + + + 44, 20 + + + 179 + + + mavlinkNumericUpDown3min + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 5 + + + False + + + 197, 288 + + + 44, 20 + + + 178 + + + mavlinkNumericUpDown2max + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 6 + + + False + + + 146, 288 + + + 44, 20 + + + 177 + + + mavlinkNumericUpDown2min + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 7 + + + False + + + 197, 262 + + + 44, 20 + + + 176 + + + mavlinkNumericUpDown1max + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 8 + + + False + + + 146, 262 + + + 44, 20 + + + 175 + + + mavlinkNumericUpDown1min + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 9 + + + NoControl + + + 314, 83 + + + 69, 23 + + + 138 + + + Manual + + + BUT_swash_manual + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 16 + + + NoControl + + + 483, 174 + + + 69, 23 + + + 167 + + + Manual + + + BUT_HS4save + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 18 + + + 17, 17 + + + 396, 93 + + + 242, 42 + + + 152 + + + HS4 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 42 + + + 17, 17 + + + 251, 95 + + + 42, 213 + + + 151 + + + HS3 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 43 + + + Zoom + + + Microsoft Sans Serif, 9pt + + + 20, 93 + + + 0, 0, 0, 0 + + + 150, 150 + + + 139 + + + Gservoloc + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 44 + + + False + + + 326, 336 + + + 44, 20 + + + 183 + + + mavlinkNumericUpDownrollmax + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 1 + + + False + + + 326, 362 + + + 44, 20 + + + 184 + + + mavlinkNumericUpDownpitchmax + + + ArdupilotMega.Controls.MavlinkNumericUpDown, ArdupilotMegaPlanner10, Version=1.1.4649.22896, Culture=neutral, PublicKeyToken=null + + + $this + + + 0 + True @@ -1570,6 +1936,6 @@ ConfigTradHeli - ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner10, Version=1.1.4561.36486, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 622b9b4553..3f798609ec 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -10,6 +10,8 @@ using log4net; using ArdupilotMega.Arduino; using ArdupilotMega.Utilities; using System.Text.RegularExpressions; +using System.Net.Security; +using System.Security.Cryptography.X509Certificates; namespace ArdupilotMega.GCSViews { @@ -84,9 +86,13 @@ namespace ArdupilotMega.GCSViews software temp = new software(); + // this is for mono to a ssl server + //ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy(); + ServicePointManager.ServerCertificateValidationCallback = new System.Net.Security.RemoteCertificateValidationCallback((sender1, certificate, chain, policyErrors) => { return true; }); + try { - + log.Info("url: "+firmwareurl); using (XmlTextReader xmlreader = new XmlTextReader(firmwareurl)) { while (xmlreader.Read()) @@ -147,6 +153,7 @@ namespace ArdupilotMega.GCSViews } catch (Exception ex) { + log.Error(ex); CustomMessageBox.Show("Failed to get Firmware List : " + ex.Message); } log.Info("FW load done"); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 4a00d3b8d2..242225c07e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -8,8 +8,8 @@ { this.components = new System.ComponentModel.Container(); System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightData)); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle(); - System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle(); + System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle(); this.contextMenuStripMap = new System.Windows.Forms.ContextMenuStrip(this.components); this.goHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); this.flyToHereAltToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem(); @@ -35,6 +35,8 @@ this.quickView2 = new ArdupilotMega.Controls.QuickView(); this.quickView1 = new ArdupilotMega.Controls.QuickView(); this.tabActions = new System.Windows.Forms.TabPage(); + this.modifyandSetAlt = new ArdupilotMega.Controls.ModifyandSet(); + this.BUT_ARM = new ArdupilotMega.Controls.MyButton(); this.BUT_script = new ArdupilotMega.Controls.MyButton(); this.BUT_joystick = new ArdupilotMega.Controls.MyButton(); this.BUT_quickmanual = new ArdupilotMega.Controls.MyButton(); @@ -229,7 +231,7 @@ this.hud1.opengl = true; this.hud1.pitch = 0F; this.hud1.roll = 0F; - this.hud1.status = 0; + this.hud1.status = false; this.hud1.streamjpg = null; this.hud1.targetalt = 0F; this.hud1.targetheading = 0F; @@ -384,10 +386,13 @@ this.quickView1.Name = "quickView1"; this.quickView1.number = 0D; this.quickView1.numberColor = System.Drawing.Color.FromArgb(((int)(((byte)(209)))), ((int)(((byte)(151)))), ((int)(((byte)(248))))); + this.toolTip1.SetToolTip(this.quickView1, resources.GetString("quickView1.ToolTip")); this.quickView1.DoubleClick += new System.EventHandler(this.quickView_DoubleClick); // // tabActions // + this.tabActions.Controls.Add(this.modifyandSetAlt); + this.tabActions.Controls.Add(this.BUT_ARM); this.tabActions.Controls.Add(this.BUT_script); this.tabActions.Controls.Add(this.BUT_joystick); this.tabActions.Controls.Add(this.BUT_quickmanual); @@ -407,6 +412,26 @@ this.tabActions.Name = "tabActions"; this.tabActions.UseVisualStyleBackColor = true; // + // modifyandSetAlt + // + this.modifyandSetAlt.ButtonText = "Change Alt"; + resources.ApplyResources(this.modifyandSetAlt, "modifyandSetAlt"); + this.modifyandSetAlt.Name = "modifyandSetAlt"; + this.modifyandSetAlt.Value = new decimal(new int[] { + 100, + 0, + 0, + 0}); + this.modifyandSetAlt.Click += new System.EventHandler(this.modifyandSetAlt_Click); + // + // BUT_ARM + // + resources.ApplyResources(this.BUT_ARM, "BUT_ARM"); + this.BUT_ARM.Name = "BUT_ARM"; + this.toolTip1.SetToolTip(this.BUT_ARM, resources.GetString("BUT_ARM.ToolTip")); + this.BUT_ARM.UseVisualStyleBackColor = true; + this.BUT_ARM.Click += new System.EventHandler(this.BUT_ARM_Click); + // // BUT_script // resources.ApplyResources(this.BUT_script, "BUT_script"); @@ -1243,8 +1268,8 @@ // // dataGridViewImageColumn1 // - dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle1; + dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle3; resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1"); this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up; this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -1252,8 +1277,8 @@ // // dataGridViewImageColumn2 // - dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; - this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle2; + dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; + this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle4; resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2"); this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down; this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch; @@ -1412,5 +1437,8 @@ private Crom.Controls.Docking.DockContainer dockContainer1; private System.Windows.Forms.ContextMenuStrip contextMenuStripDockContainer; private System.Windows.Forms.ToolStripMenuItem resetToolStripMenuItem; + private Controls.MyButton BUT_ARM; + private Controls.ModifyandSet modifyandSetAlt; + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index f07ae2150c..2048b000d4 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -68,13 +68,12 @@ namespace ArdupilotMega.GCSViews internal static GMapOverlay kmlpolygons; internal static GMapOverlay geofence; - Dictionary formguids = new Dictionary(); + Dictionary formguids = new Dictionary(); bool huddropout = false; bool huddropoutresize = false; private DockStateSerializer _serializer = null; - DockableFormInfo dockhud; List trackPoints = new List(); @@ -99,8 +98,11 @@ namespace ArdupilotMega.GCSViews threadrun = 0; MainV2.comPort.logreadmode = false; MainV2.config["FlightSplitter"] = hud1.Width; - _serializer.Save(); - SaveWindowLayout(); + if (!MainV2.MONO) + { + _serializer.Save(); + SaveWindowLayout(); + } System.Threading.Thread.Sleep(100); base.Dispose(disposing); } @@ -230,25 +232,31 @@ namespace ArdupilotMega.GCSViews } catch { } - SetupDocking(); - - if (File.Exists(_serializer.SavePath) == true) + if (MainV2.MONO) { - try - { - _serializer.Load(true, GetFormFromGuid); - } - catch { } + MainH.Dock = DockStyle.Fill; + MainH.Visible = true; } + else + { + SetupDocking(); - cleanupDocks(); + if (File.Exists(_serializer.SavePath) == true) + { + try + { + _serializer.Load(true, GetFormFromGuid); + } + catch { } + } + } } void SetupDocking() { this.SuspendLayout(); - dockhud = CreateFormAndGuid(dockContainer1, hud1, "fd_hud_guid"); + DockableFormInfo dockhud = CreateFormAndGuid(dockContainer1, hud1, "fd_hud_guid"); DockableFormInfo dockmap = CreateFormAndGuid(dockContainer1, tableMap, "fd_map_guid"); DockableFormInfo dockquick = CreateFormAndGuid(dockContainer1, tabQuick, "fd_quick_guid"); DockableFormInfo dockactions = CreateFormAndGuid(dockContainer1, tabActions, "fd_actions_guid"); @@ -256,7 +264,6 @@ namespace ArdupilotMega.GCSViews DockableFormInfo dockstatus = CreateFormAndGuid(dockContainer1, tabStatus, "fd_status_guid"); DockableFormInfo docktlogs = CreateFormAndGuid(dockContainer1, tabTLogs, "fd_tlogs_guid"); - dockContainer1.DockForm(dockmap, DockStyle.Fill, zDockMode.Outer); dockContainer1.DockForm(dockquick, DockStyle.Right, zDockMode.Outer); dockContainer1.DockForm(dockhud, DockStyle.Left, zDockMode.Outer); @@ -275,6 +282,8 @@ namespace ArdupilotMega.GCSViews dockContainer1.SetHeight(dockhud, hud1.Height); + dockContainer1.SetWidth(dockguages, 110); + this.ResumeLayout(); } @@ -289,7 +298,6 @@ namespace ArdupilotMega.GCSViews info.ShowContextMenuButton = false; } - dockContainer1.Invalidate(); } void SaveWindowLayout() @@ -319,7 +327,7 @@ namespace ArdupilotMega.GCSViews object fieldValue; try { - fieldValue = field.GetValue(thisBoxed,null); // Get value + fieldValue = field.GetValue(thisBoxed, null); // Get value } catch { continue; } @@ -329,10 +337,30 @@ namespace ArdupilotMega.GCSViews xmlwriter.WriteElementString(field.Name, fieldValue.ToString()); } - // DockableContainer dockcont = info as DockableContainer; + thisBoxed = info.DockableForm; + test = thisBoxed.GetType(); + + foreach (var field in test.GetProperties()) + { + // field.Name has the field's name. + object fieldValue; + try + { + fieldValue = field.GetValue(thisBoxed, null); // Get value + + + // Get the TypeCode enumeration. Multiple types get mapped to a common typecode. + TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType()); + + xmlwriter.WriteElementString(field.Name, fieldValue.ToString()); + } + catch { continue; } + } + + // DockableContainer dockcont = info as DockableContainer; + + // dockContainer1. - // dockContainer1. - xmlwriter.WriteEndElement(); } @@ -342,11 +370,12 @@ namespace ArdupilotMega.GCSViews xmlwriter.Close(); } - DockableFormInfo CreateFormAndGuid(DockContainer dock, Control ctl, string configguidref) + DockableFormInfo CreateFormAndGuid(DockContainer dock, Control ctl, string configguidref) { Guid gu = GetOrCreateGuid(configguidref); Form frm; - if (formguids.ContainsKey(gu)) + + if (formguids.ContainsKey(gu) && !formguids[gu].IsDisposed) { frm = formguids[gu]; } @@ -355,9 +384,18 @@ namespace ArdupilotMega.GCSViews frm = CreateFormFromControl(ctl); frm.AutoScroll = true; formguids[gu] = frm; - } + } - return dock.Add(frm, Crom.Controls.Docking.zAllowedDock.All, gu); + frm.FormBorderStyle = FormBorderStyle.SizableToolWindow; + frm.TopLevel = false; + + DockableFormInfo answer = dock.Add(frm, Crom.Controls.Docking.zAllowedDock.All, gu); + + answer.ShowCloseButton = false; + + answer.ShowContextMenuButton = false; + + return answer; } Guid GetOrCreateGuid(string configname) @@ -367,7 +405,7 @@ namespace ArdupilotMega.GCSViews MainV2.config[configname] = Guid.NewGuid().ToString(); } - return new Guid(MainV2.config[configname].ToString()); + return new Guid(MainV2.config[configname].ToString()); } Form GetFormFromGuid(Guid id) @@ -418,7 +456,7 @@ namespace ArdupilotMega.GCSViews { newform.Text = "Hud"; } - if (ctl is myGMAP) + if (ctl is myGMAP) { newform.Text = "Map"; } @@ -433,7 +471,7 @@ namespace ArdupilotMega.GCSViews // localise it Control tabStatus = sender as Control; - // tabStatus.SuspendLayout(); + // tabStatus.SuspendLayout(); //foreach (Control temp in tabStatus.Controls) { @@ -517,7 +555,7 @@ namespace ArdupilotMega.GCSViews tabStatus.Width = x; - // tabStatus.ResumeLayout(); + // tabStatus.ResumeLayout(); } public void Activate() @@ -550,7 +588,7 @@ namespace ArdupilotMega.GCSViews hud1.Enabled = false; hud1.Visible = false; } - // hud1.Location = new Point(-1000,-1000); + // hud1.Location = new Point(-1000,-1000); ZedGraphTimer.Stop(); } @@ -718,7 +756,7 @@ namespace ArdupilotMega.GCSViews LogPlayBackSpeed = 0.01; try { - ts = Math.Min((act / LogPlayBackSpeed),1000); + ts = Math.Min((act / LogPlayBackSpeed), 1000); } catch { } @@ -759,7 +797,7 @@ namespace ArdupilotMega.GCSViews tunning = DateTime.Now; } - + if (MainV2.comPort.logplaybackfile != null && MainV2.comPort.logplaybackfile.BaseStream.Position == MainV2.comPort.logplaybackfile.BaseStream.Length) { @@ -779,18 +817,18 @@ namespace ArdupilotMega.GCSViews } } - + try { - // Console.WriteLine(DateTime.Now.Millisecond); + // Console.WriteLine(DateTime.Now.Millisecond); updateBindingSource(); - // Console.WriteLine(DateTime.Now.Millisecond + " done "); + // Console.WriteLine(DateTime.Now.Millisecond + " done "); if (ArdupilotMega.Controls.OpenGLtest.instance != null) { - ArdupilotMega.Controls.OpenGLtest.instance.rpy = new OpenTK.Vector3(MainV2.cs.roll,MainV2.cs.pitch,MainV2.cs.yaw); - ArdupilotMega.Controls.OpenGLtest.instance.LocationCenter = new PointLatLngAlt(MainV2.cs.lat,MainV2.cs.lng,MainV2.cs.alt,"here"); + ArdupilotMega.Controls.OpenGLtest.instance.rpy = new OpenTK.Vector3(MainV2.cs.roll, MainV2.cs.pitch, MainV2.cs.yaw); + ArdupilotMega.Controls.OpenGLtest.instance.LocationCenter = new PointLatLngAlt(MainV2.cs.lat, MainV2.cs.lng, MainV2.cs.alt, "here"); } if (tunning.AddMilliseconds(50) < DateTime.Now && CB_tuning.Checked == true) @@ -847,12 +885,12 @@ namespace ArdupilotMega.GCSViews if (route.Points.Count > int.Parse(MainV2.config["NUM_tracklength"].ToString())) { - // trackPoints.RemoveRange(0, trackPoints.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString())); + // trackPoints.RemoveRange(0, trackPoints.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString())); route.Points.RemoveRange(0, route.Points.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString())); } if (MainV2.cs.lat != 0) { - // trackPoints.Add(currentloc); + // trackPoints.Add(currentloc); route.Points.Add(currentloc); } @@ -880,26 +918,28 @@ namespace ArdupilotMega.GCSViews //Console.WriteLine("Doing FD WP's"); updateMissionRouteMarkers(); - if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null) + foreach (MAVLink.mavlink_mission_item_t plla in MainV2.comPort.wps.Values) { - FlightPlanner.pointlist.Clear(); - FlightPlanner.pointlist.AddRange(MainV2.comPort.wps); - } - - foreach (PointLatLngAlt plla in FlightPlanner.pointlist) - { - if (plla == null) - break; - if (plla.Lng == 0 || plla.Lat == 0) + if (plla.x == 0 || plla.y == 0) continue; - if (plla.Tag.StartsWith("ROI")) + if (plla.command == (byte)MAVLink.MAV_CMD.ROI) { - addpolygonmarkerred(plla.Tag, plla.Lng, plla.Lat, (int)plla.Alt, plla.color, routes); + addpolygonmarkerred(plla.seq.ToString(), plla.y, plla.x, (int)plla.z, Color.Red, routes); continue; } - addpolygonmarker(plla.Tag, plla.Lng, plla.Lat, (int)plla.Alt,plla.color,polygons); + string tag = plla.seq.ToString(); + if (plla.seq == 0 && plla.current != 2) + { + tag = "Home"; + } + if (plla.current == 2) + { + continue; + } + + addpolygonmarker(tag, plla.y, plla.x, (int)plla.z, Color.White, polygons); } RegeneratePolygon(); @@ -915,12 +955,12 @@ namespace ArdupilotMega.GCSViews if (routes.Markers.Count != 1) { routes.Markers.Clear(); - routes.Markers.Add( new GMapMarkerCross(currentloc)); + routes.Markers.Add(new GMapMarkerCross(currentloc)); } - if (MainV2.cs.mode.ToLower() == "guided" && MainV2.cs.GuidedModeWP != null && MainV2.cs.GuidedModeWP.Lat != 0) + if (MainV2.cs.mode.ToLower() == "guided" && MainV2.comPort.GuidedMode.x != 0) { - addpolygonmarker("Guided Mode", MainV2.cs.GuidedModeWP.Lng, MainV2.cs.GuidedModeWP.Lat, (int)MainV2.cs.GuidedModeWP.Alt, Color.Blue, routes); + addpolygonmarker("Guided Mode", MainV2.comPort.GuidedMode.y, MainV2.comPort.GuidedMode.x, (int)MainV2.comPort.GuidedMode.z, Color.Blue, routes); } if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) @@ -999,7 +1039,7 @@ namespace ArdupilotMega.GCSViews { if (playing) { - if (BUT_playlog.Text == "Pause") + if (BUT_playlog.Text == "Pause") return; this.BeginInvoke((System.Windows.Forms.MethodInvoker)delegate() @@ -1091,18 +1131,18 @@ namespace ArdupilotMega.GCSViews GMapMarkerRect mBorders = new GMapMarkerRect(point); { - - mBorders.InnerMarker = m; - try - { - mBorders.wprad = (int)(float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString()) / MainV2.cs.multiplierdist); - } - catch { } - mBorders.MainMap = gMapControl1; - if (color.HasValue) - { - mBorders.Color = color.Value; - } + + mBorders.InnerMarker = m; + try + { + mBorders.wprad = (int)(float.Parse(ArdupilotMega.MainV2.config["TXT_WPRad"].ToString()) / MainV2.cs.multiplierdist); + } + catch { } + mBorders.MainMap = gMapControl1; + if (color.HasValue) + { + mBorders.Color = color.Value; + } } overlay.Markers.Add(m); @@ -1284,7 +1324,7 @@ namespace ArdupilotMega.GCSViews private void BUT_clear_track_Click(object sender, EventArgs e) { - if (route !=null) + if (route != null) route.Points.Clear(); } @@ -1308,7 +1348,7 @@ namespace ArdupilotMega.GCSViews { ((Button)sender).Enabled = false; #if MAVLINK10 - comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text),1,0,1,0,0,0,0); + comPort.doCommand((MAVLink.MAV_CMD)Enum.Parse(typeof(MAVLink.MAV_CMD), CMB_action.Text), 1, 0, 1, 0, 0, 0, 0); #else comPort.doAction((MAVLink.MAV_ACTION)Enum.Parse(typeof(MAVLink.MAV_ACTION), "MAV_ACTION_" + CMB_action.Text)); #endif @@ -1387,11 +1427,11 @@ namespace ArdupilotMega.GCSViews return; } - if (MainV2.cs.GuidedModeWP.Alt == 0) + if (MainV2.comPort.GuidedMode.z == 0) { flyToHereAltToolStripMenuItem_Click(null, null); - if (MainV2.cs.GuidedModeWP.Alt == 0) + if (MainV2.comPort.GuidedMode.z == 0) return; } @@ -1404,15 +1444,13 @@ namespace ArdupilotMega.GCSViews Locationwp gotohere = new Locationwp(); gotohere.id = (byte)MAVLink.MAV_CMD.WAYPOINT; - gotohere.alt = (float)(MainV2.cs.GuidedModeWP.Alt); // back to m + gotohere.alt = (float)(MainV2.comPort.GuidedMode.z); // back to m gotohere.lat = (float)(gotolocation.Lat); gotohere.lng = (float)(gotolocation.Lng); try { MainV2.comPort.setGuidedModeWP(gotohere); - - MainV2.cs.GuidedModeWP = new PointLatLngAlt(gotohere.lat, gotohere.lng, gotohere.alt, "Guided Mode"); } catch (Exception ex) { MainV2.giveComport = false; CustomMessageBox.Show("Error sending command : " + ex.Message); } @@ -1450,8 +1488,8 @@ namespace ArdupilotMega.GCSViews catch { } } } - - private void FlightData_ParentChanged(object sender, EventArgs e) + + private void FlightData_ParentChanged(object sender, EventArgs e) { if (MainV2.cam != null) { @@ -1528,7 +1566,7 @@ namespace ArdupilotMega.GCSViews } else { - // BUT_clear_track_Click(sender, e); + // BUT_clear_track_Click(sender, e); MainV2.comPort.logreadmode = true; list1.Clear(); list2.Clear(); @@ -1665,11 +1703,7 @@ namespace ArdupilotMega.GCSViews try { ((Button)sender).Enabled = false; -#if MAVLINK10 - MainV2.comPort.setMode("Auto"); -#else - comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_AUTO); -#endif + MainV2.comPort.setMode("Auto"); } catch { CustomMessageBox.Show("The Command failed to execute"); } ((Button)sender).Enabled = true; @@ -1680,11 +1714,7 @@ namespace ArdupilotMega.GCSViews try { ((Button)sender).Enabled = false; -#if MAVLINK10 - MainV2.comPort.setMode("RTL"); -#else - comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_RETURN); -#endif + MainV2.comPort.setMode("RTL"); } catch { CustomMessageBox.Show("The Command failed to execute"); } ((Button)sender).Enabled = true; @@ -1695,14 +1725,11 @@ namespace ArdupilotMega.GCSViews try { ((Button)sender).Enabled = false; -#if MAVLINK10 if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) - MainV2.comPort.setMode("Manual"); + MainV2.comPort.setMode("Manual"); if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) MainV2.comPort.setMode("Stabilize"); -#else - comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_MANUAL); -#endif + } catch { CustomMessageBox.Show("The Command failed to execute"); } ((Button)sender).Enabled = true; @@ -1745,7 +1772,7 @@ namespace ArdupilotMega.GCSViews void dropout_FormClosed(object sender, FormClosedEventArgs e) { - dockhud.DockableForm.Controls.Add(hud1); + GetFormFromGuid(GetOrCreateGuid("fd_hud_guid")).Controls.Add(hud1); huddropout = false; } @@ -2024,7 +2051,7 @@ namespace ArdupilotMega.GCSViews { HUD.Custom cust = new HUD.Custom(); - string prefix = ((CheckBox)sender).Name +": "; + string prefix = ((CheckBox)sender).Name + ": "; if (MainV2.config["hud1_useritem_" + ((CheckBox)sender).Name] != null) prefix = (string)MainV2.config["hud1_useritem_" + ((CheckBox)sender).Name]; @@ -2328,11 +2355,11 @@ print 'Roll complete' "; - // CustomMessageBox.Show("This is Very ALPHA"); + // CustomMessageBox.Show("This is Very ALPHA"); Form scriptedit = new Form(); - scriptedit.Size = new System.Drawing.Size(500,500); + scriptedit.Size = new System.Drawing.Size(500, 500); TextBox tb = new TextBox(); @@ -2341,8 +2368,8 @@ print 'Roll complete' tb.ScrollBars = ScrollBars.Both; tb.Multiline = true; - tb.Location = new Point(0,0); - tb.Size = new System.Drawing.Size(scriptedit.Size.Width-30,scriptedit.Size.Height-30); + tb.Location = new Point(0, 0); + tb.Size = new System.Drawing.Size(scriptedit.Size.Width - 30, scriptedit.Size.Height - 30); scriptedit.Controls.Add(tb); @@ -2485,7 +2512,7 @@ print 'Roll complete' // set databinding for value ((QuickView)((CheckBox)sender).Tag).DataBindings.Clear(); - ((QuickView)((CheckBox)sender).Tag).DataBindings.Add(new System.Windows.Forms.Binding("number",this.bindingSource1, ((CheckBox)sender).Name, true)); + ((QuickView)((CheckBox)sender).Tag).DataBindings.Add(new System.Windows.Forms.Binding("number", this.bindingSource1, ((CheckBox)sender).Name, true)); // close selection form ((Form)((CheckBox)sender).Parent).Close(); @@ -2520,11 +2547,11 @@ print 'Roll complete' return; } - MainV2.cs.GuidedModeWP.Alt = intalt; + MainV2.comPort.GuidedMode.z = intalt; if (MainV2.cs.mode == "Guided") { - MainV2.comPort.setGuidedModeWP(new Locationwp() { alt = (float)MainV2.cs.GuidedModeWP.Alt, lat = (float)MainV2.cs.GuidedModeWP.Lat, lng = (float)MainV2.cs.GuidedModeWP.Lng }); + MainV2.comPort.setGuidedModeWP(new Locationwp() { alt = (float)MainV2.comPort.GuidedMode.z, lat = (float)MainV2.comPort.GuidedMode.x, lng = (float)MainV2.comPort.GuidedMode.y }); } } @@ -2545,7 +2572,7 @@ print 'Roll complete' splitContainer1.Panel2.Controls.Add(but); splitContainer1.Panel2.Controls.Add(sc.Control); ThemeManager.ApplyThemeTo(sc.Control); - + sc.Control.Dock = DockStyle.Fill; sc.Control.Visible = true; @@ -2598,11 +2625,11 @@ print 'Roll complete' private void hud1_Resize(object sender, EventArgs e) { - Console.WriteLine("HUD resize "+ hud1.Width + " " + hud1.Height); + //Console.WriteLine("HUD resize "+ hud1.Width + " " + hud1.Height); try { - // dockContainer1.SetHeight(dockhud, hud1.Height); + // dockContainer1.SetHeight(dockhud, hud1.Height); } catch { } } @@ -2611,8 +2638,25 @@ print 'Roll complete' { dockContainer1.Clear(); SetupDocking(); - cleanupDocks(); this.Refresh(); } + + private void BUT_ARM_Click(object sender, EventArgs e) + { + if (!MainV2.comPort.BaseStream.IsOpen) + return; + + // arm the MAV + MainV2.comPort.doARM(MainV2.cs.armed); + } + + private void modifyandSetAlt_Click(object sender, EventArgs e) + { + int newalt = (int)modifyandSetAlt.Value; + + MainV2.comPort.setNewWPAlt(new Locationwp() { alt = newalt }); + + //MainV2.comPort.setNextWPTargetAlt((ushort)MainV2.cs.wpno, newalt); + } } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index 7325e52b19..ff7b77cd3b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -121,6 +121,15 @@ 290, 17 + + 175, 92 + + + contextMenuStripMap + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + 174, 22 @@ -145,17 +154,8 @@ Flight Planner - - 175, 92 - - - contextMenuStripMap - - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 186, 70 + 354, 0 @@ -176,6 +176,847 @@ 542, 17 + + 177, 158 + + + contextMenuStripHud + + + System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + 153, 17 + + + Fill + + + 0, 0 + + + 358, 310 + + + + 1 + + + hud1 + + + ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + SubMainLeft.Panel1 + + + 0 + + + SubMainLeft.Panel1 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SubMainLeft + + + 0 + + + True + + + Top + + + 3, 278 + + + 327, 55 + + + 10 + + + quickView6 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 0 + + + Top + + + 3, 223 + + + 327, 55 + + + 9 + + + quickView5 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 1 + + + Top + + + 3, 168 + + + 327, 55 + + + 8 + + + quickView4 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 2 + + + Top + + + 3, 113 + + + 327, 55 + + + 3 + + + quickView3 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 3 + + + Top + + + 3, 58 + + + 327, 55 + + + 1 + + + quickView2 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 4 + + + Top + + + 3, 3 + + + 327, 55 + + + 1 + + + 445, 17 + + + Double Click me to change + + + quickView1 + + + ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabQuick + + + 5 + + + 4, 22 + + + 3, 3, 3, 3 + + + 350, 117 + + + 4 + + + Quick + + + tabQuick + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 0 + + + modifyandSetAlt + + + ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 0 + + + BUT_ARM + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 1 + + + BUT_script + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 2 + + + BUT_joystick + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 3 + + + BUT_quickmanual + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 4 + + + BUT_quickrtl + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 5 + + + BUT_quickauto + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 6 + + + CMB_setwp + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 7 + + + BUT_setwp + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 8 + + + CMB_modes + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 9 + + + BUT_setmode + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 10 + + + BUT_clear_track + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 11 + + + CMB_action + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabActions + + + 12 + + + BUT_Homealt + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 13 + + + BUT_RAWSensor + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 14 + + + BUTrestartmission + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 15 + + + BUTactiondo + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 16 + + + 4, 22 + + + 350, 117 + + + 2 + + + Actions + + + tabActions + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 1 + + + Gvspeed + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 0 + + + Gheading + + + ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 1 + + + Galt + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 2 + + + Gspeed + + + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabGauges + + + 3 + + + 4, 22 + + + 3, 3, 3, 3 + + + 350, 117 + + + 0 + + + Gauges + + + tabGauges + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 2 + + + True + + + 4, 22 + + + 3, 3, 3, 3 + + + 350, 117 + + + 1 + + + Status + + + tabStatus + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 3 + + + lbl_playbackspeed + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 0 + + + lbl_logpercent + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 1 + + + NUM_playbackspeed + + + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 2 + + + BUT_log2kml + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 3 + + + tracklog + + + System.Windows.Forms.TrackBar, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabTLogs + + + 4 + + + BUT_playlog + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 5 + + + BUT_loadtelem + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabTLogs + + + 6 + + + 4, 22 + + + 350, 117 + + + 3 + + + Telemetry Logs + + + tabTLogs + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 4 + + + Fill + + + 0, 0 + + + 0, 0 + + + 358, 143 + + + 84 + + + tabControl1 + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SubMainLeft.Panel2 + + + 0 + + + SubMainLeft.Panel2 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + SubMainLeft + + + 1 + + + 360, 461 + + + 312 + + + 0 + + + SubMainLeft + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + MainH.Panel1 + + + 0 + + + MainH.Panel1 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + MainH + + + 0 + + + 360 + + + Single + + + 1 + + + splitContainer1 + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + + 0 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + + 1 + + + Fill + + + 0, 0 + + + 2 + + + 288, 459 + + + 75 + + + tableMap + + + System.Windows.Forms.TableLayoutPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + MainH.Panel2 + + + 0 + + + <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30,Absolute,20" /></TableLayoutSettings> + + + MainH.Panel2 + + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + MainH + + + 1 + + + 654, 461 + + + 360 + + + 68 + + + False + + + MainH + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + 176, 22 @@ -212,237 +1053,74 @@ User Items - - 177, 158 + + False - - contextMenuStripHud + + 216, 90 - - System.Windows.Forms.ContextMenuStrip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 114, 29 - - 153, 17 + + 80 + + + modifyandSetAlt + + + ArdupilotMega.Controls.ModifyandSet, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + + 0 + + + 445, 17 - - Fill + + Microsoft Sans Serif, 8.25pt - - 0, 0 + + NoControl - - 358, 263 + + 111, 90 - - + + 45, 23 + + + 79 + + + Arm/ Disarm + + + Arm the Mav + + + BUT_ARM + + + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + tabActions + + 1 - - hud1 - - - ArdupilotMega.Controls.HUD, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - SubMainLeft.Panel1 - - - 0 - - - SubMainLeft.Panel1 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SubMainLeft - - - 0 - - - True - - - Top - - - 3, 278 - - - 327, 55 - - - 5 - - - quickView6 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 0 - - - Top - - - 3, 223 - - - 327, 55 - - - 4 - - - quickView5 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 1 - - - Top - - - 3, 168 - - - 327, 55 - - - 3 - - - quickView4 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 2 - - - Top - - - 3, 113 - - - 327, 55 - - - 2 - - - quickView3 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 3 - - - Top - - - 3, 58 - - - 327, 55 - - - 1 - - - quickView2 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 4 - - - Top - - - 3, 3 - - - 327, 55 - - - 0 - - - quickView1 - - - ArdupilotMega.Controls.QuickView, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null - - - tabQuick - - - 5 - - - 4, 22 - - - 3, 3, 3, 3 - - - 350, 94 - - - 4 - - - Quick - - - tabQuick - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 0 - NoControl - 17, 93 + 4, 91 - 66, 23 + 46, 23 78 @@ -454,22 +1132,22 @@ BUT_script - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 0 + 2 NoControl - 101, 93 + 56, 91 - 66, 23 + 49, 23 77 @@ -477,9 +1155,6 @@ Joystick - - 445, 17 - Setup and enable your joystick @@ -487,22 +1162,22 @@ BUT_joystick - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 1 + 3 NoControl - 173, 35 + 147, 35 - 57, 23 + 47, 23 76 @@ -517,22 +1192,22 @@ BUT_quickmanual - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 2 + 4 NoControl - 173, 64 + 147, 64 - 57, 23 + 47, 23 75 @@ -547,22 +1222,22 @@ BUT_quickrtl - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 3 + 5 NoControl - 173, 6 + 147, 6 - 57, 23 + 47, 23 74 @@ -577,13 +1252,13 @@ BUT_quickauto - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 4 + 6 0 (Home) @@ -592,7 +1267,7 @@ 4, 35 - 91, 21 + 76, 21 72 @@ -607,16 +1282,16 @@ tabActions - 5 + 7 NoControl - 101, 35 + 86, 35 - 66, 23 + 55, 23 73 @@ -631,19 +1306,19 @@ BUT_setwp - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 6 + 8 4, 64 - 91, 21 + 76, 21 70 @@ -658,16 +1333,16 @@ tabActions - 7 + 9 NoControl - 101, 64 + 86, 64 - 66, 23 + 55, 23 71 @@ -682,22 +1357,22 @@ BUT_setmode - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 8 + 10 NoControl - 236, 93 + 162, 90 - 97, 23 + 47, 23 52 @@ -712,19 +1387,19 @@ BUT_clear_track - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 9 + 11 4, 6 - 91, 21 + 76, 21 59 @@ -739,16 +1414,16 @@ tabActions - 10 + 12 NoControl - 236, 6 + 200, 6 - 97, 23 + 69, 23 69 @@ -763,22 +1438,22 @@ BUT_Homealt - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 11 + 13 NoControl - 236, 64 + 200, 64 - 97, 23 + 69, 23 68 @@ -793,22 +1468,22 @@ BUT_RAWSensor - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 12 + 14 NoControl - 236, 35 + 200, 35 - 97, 23 + 69, 23 63 @@ -823,22 +1498,22 @@ BUTrestartmission - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 13 + 15 NoControl - 101, 6 + 86, 6 - 66, 23 + 55, 23 60 @@ -853,37 +1528,13 @@ BUTactiondo - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabActions - 14 - - - 4, 22 - - - 350, 94 - - - 2 - - - Actions - - - tabActions - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 1 + 16 Zoom @@ -907,7 +1558,7 @@ Gvspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabGauges @@ -937,7 +1588,7 @@ Gheading - ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.HSI, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabGauges @@ -967,7 +1618,7 @@ Galt - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabGauges @@ -1000,7 +1651,7 @@ Gspeed - AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + AGaugeApp.AGauge, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabGauges @@ -1008,63 +1659,6 @@ 3 - - 4, 22 - - - 3, 3, 3, 3 - - - 350, 94 - - - 0 - - - Gauges - - - tabGauges - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 2 - - - True - - - 4, 22 - - - 3, 3, 3, 3 - - - 350, 94 - - - 1 - - - Status - - - tabStatus - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 3 - Top, Right @@ -1084,7 +1678,7 @@ lbl_playbackspeed - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1111,7 +1705,7 @@ lbl_logpercent - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1138,7 +1732,7 @@ NUM_playbackspeed - ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1165,7 +1759,7 @@ BUT_log2kml - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1219,7 +1813,7 @@ BUT_playlog - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1246,7 +1840,7 @@ BUT_loadtelem - ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null tabTLogs @@ -1254,111 +1848,6 @@ 6 - - 4, 22 - - - 350, 94 - - - 3 - - - Telemetry Logs - - - tabTLogs - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 4 - - - Fill - - - 0, 0 - - - 0, 0 - - - 358, 120 - - - 84 - - - tabControl1 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SubMainLeft.Panel2 - - - 0 - - - SubMainLeft.Panel2 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - SubMainLeft - - - 1 - - - 360, 391 - - - 265 - - - 0 - - - SubMainLeft - - - System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - MainH.Panel1 - - - 0 - - - MainH.Panel1 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - MainH - - - 0 - - - 360 - - - Single - - - 1 - Fill @@ -1378,7 +1867,7 @@ 4, 4, 4, 4 - 448, 210 + 280, 210 67 @@ -1432,7 +1921,7 @@ lbl_winddir - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1462,7 +1951,7 @@ lbl_windvel - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1477,7 +1966,7 @@ NoControl - -1, 320 + -1, 390 43, 12 @@ -1495,7 +1984,7 @@ lbl_hdop - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1510,7 +1999,7 @@ NoControl - -1, 338 + -1, 408 40, 12 @@ -1528,7 +2017,7 @@ lbl_sats - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1546,7 +2035,7 @@ 0, 0, 0, 0 - 448, 350 + 280, 420 @@ -1700,7 +2189,7 @@ gMapControl1 - ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null splitContainer1.Panel2 @@ -1721,7 +2210,7 @@ 1 - 448, 350 + 280, 420 210 @@ -1741,6 +2230,117 @@ 0 + + TXT_lat + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 0 + + + Zoomlevel + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 1 + + + label1 + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 2 + + + TXT_long + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 3 + + + TXT_alt + + + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null + + + panel1 + + + 4 + + + CHK_autopan + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 5 + + + CB_tuning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 6 + + + Fill + + + 1, 428 + + + 0, 0, 0, 0 + + + 286, 30 + + + 0 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + + 1 + Bottom, Left @@ -1763,7 +2363,7 @@ TXT_lat - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null panel1 @@ -1820,7 +2420,7 @@ label1 - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null panel1 @@ -1850,7 +2450,7 @@ TXT_long - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null panel1 @@ -1880,7 +2480,7 @@ TXT_alt - ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null panel1 @@ -1960,99 +2560,6 @@ 6 - - Fill - - - 1, 358 - - - 0, 0, 0, 0 - - - 454, 30 - - - 0 - - - panel1 - - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tableMap - - - 1 - - - Fill - - - 0, 0 - - - 2 - - - 456, 389 - - - 75 - - - tableMap - - - System.Windows.Forms.TableLayoutPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - MainH.Panel2 - - - 0 - - - <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30,Absolute,20" /></TableLayoutSettings> - - - MainH.Panel2 - - - System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - MainH - - - 1 - - - 822, 391 - - - 360 - - - 68 - - - False - - - MainH - - - System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 3 - Up @@ -2071,12 +2578,6 @@ 714, 17 - - 152, 22 - - - Reset - 103, 26 @@ -2110,6 +2611,12 @@ 4 + + 152, 22 + + + Reset + True @@ -2222,6 +2729,6 @@ FlightData - System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4646.13106, Culture=neutral, PublicKeyToken=null + System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4653.13270, Culture=neutral, PublicKeyToken=null \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index 9ace26ea96..de9a73d391 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -38,7 +38,7 @@ namespace ArdupilotMega.GCSViews bool polygongridmode = false; Hashtable param = new Hashtable(); - public static List pointlist = new List(); // used to calc distance + List pointlist = new List(); // used to calc distance static public Object thisLock = new Object(); private ComponentResourceManager rm = new ComponentResourceManager(typeof(FlightPlanner)); @@ -925,7 +925,7 @@ namespace ArdupilotMega.GCSViews // this is to share the current mission with the data tab pointlist = new List(); - + System.Diagnostics.Debug.WriteLine(DateTime.Now); try { @@ -1921,7 +1921,7 @@ namespace ArdupilotMega.GCSViews MainMap.Invalidate(false); int answer; - if (int.TryParse(item.Tag.ToString(), out answer)) + if (item.Tag != null && int.TryParse(item.Tag.ToString(), out answer)) { try { @@ -2782,9 +2782,9 @@ namespace ArdupilotMega.GCSViews routes.Markers.Add(new GMapMarkerQuad(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing)); } - if (MainV2.cs.mode.ToLower() == "guided" && MainV2.cs.GuidedModeWP != null && MainV2.cs.GuidedModeWP.Lat != 0) + if (MainV2.cs.mode.ToLower() == "guided" && MainV2.comPort.GuidedMode.x != 0) { - addpolygonmarker("Guided Mode", MainV2.cs.GuidedModeWP.Lng, MainV2.cs.GuidedModeWP.Lat, (int)MainV2.cs.GuidedModeWP.Alt, Color.Red, routes); + addpolygonmarker("Guided Mode", MainV2.comPort.GuidedMode.y, MainV2.comPort.GuidedMode.x, (int)MainV2.comPort.GuidedMode.z, Color.Blue, routes); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index c583701f2f..822e746803 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -565,10 +565,8 @@ namespace ArdupilotMega.GCSViews DateTime lastdata = DateTime.MinValue; - #if MAVLINK10 // set enable hil status flag - sends base_mode = 0 MainV2.comPort.setMode(new MAVLink.mavlink_set_mode_t() { target_system = MainV2.comPort.sysid }, MAVLink.MAV_MODE_FLAG.HIL_ENABLED); -#endif while (threadrun == 1) { diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs index 543d5162a2..46bf9ac45b 100644 --- a/Tools/ArdupilotMegaPlanner/Log.cs +++ b/Tools/ArdupilotMegaPlanner/Log.cs @@ -62,6 +62,23 @@ namespace ArdupilotMega InitializeComponent(); } + private void waitandsleep(int time) + { + DateTime start = DateTime.Now; + + while ((DateTime.Now - start).TotalMilliseconds < time) + { + try + { + if (comPort.BytesToRead > 0) + { + return; + } + } + catch { threadrun = false; return; } + } + } + private void readandsleep(int time) { DateTime start = DateTime.Now; @@ -85,12 +102,15 @@ namespace ArdupilotMega comPort = MainV2.comPort.BaseStream; - //comPort.ReceivedBytesThreshold = 50; - //comPort.ReadBufferSize = 1024 * 1024; try { + comPort.toggleDTR(); - //comPort.Open(); + + comPort.DiscardInBuffer(); + + // 10 sec + waitandsleep(10000); } catch (Exception ex) { @@ -104,7 +124,7 @@ namespace ArdupilotMega threadrun = true; - readandsleep(2500); + readandsleep(100); try { diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index c4536d0712..3bb6591379 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -1106,7 +1106,6 @@ namespace ArdupilotMega MainV2.cs.linkqualitygcs = (ushort)(MainV2.cs.linkqualitygcs * 0.8f); linkqualitytime = DateTime.Now; - int checkthis; GCSViews.FlightData.myhud.Invalidate(); } } @@ -1118,7 +1117,7 @@ namespace ArdupilotMega { type = (byte)MAVLink.MAV_TYPE.GCS, autopilot = (byte)MAVLink.MAV_AUTOPILOT.ARDUPILOTMEGA, - mavlink_version = 3 + mavlink_version = 3, }; comPort.sendPacket(htb); @@ -1474,11 +1473,9 @@ namespace ArdupilotMega SharpKml.Dom.CoordinateCollection coords = new SharpKml.Dom.CoordinateCollection(); - foreach (var point in GCSViews.FlightPlanner.pointlist) + foreach (var point in MainV2.comPort.wps.Values) { - if (point != null) - coords.Add(new SharpKml.Base.Vector(point.Lat, point.Lng, point.Alt)); - + coords.Add(new SharpKml.Base.Vector(point.x, point.y, point.z)); } SharpKml.Dom.LineString ls = new SharpKml.Dom.LineString(); @@ -1716,8 +1713,8 @@ namespace ArdupilotMega { var fi = new FileInfo(path); - string LocalVersion = ""; - string WebVersion = ""; + Version LocalVersion = new Version(); + Version WebVersion = new Version(); if (File.Exists(path)) { @@ -1725,7 +1722,7 @@ namespace ArdupilotMega { using (StreamReader sr = new StreamReader(fs)) { - LocalVersion = sr.ReadLine(); + LocalVersion = new Version(sr.ReadLine()); sr.Close(); } fs.Close(); @@ -1734,7 +1731,7 @@ namespace ArdupilotMega using (StreamReader sr = new StreamReader(response.GetResponseStream())) { - WebVersion = sr.ReadLine(); + WebVersion = new Version(sr.ReadLine()); sr.Close(); } @@ -1743,7 +1740,7 @@ namespace ArdupilotMega log.Info("New file Check: local " + LocalVersion + " vs Remote " + WebVersion); - if (LocalVersion != WebVersion) + if (LocalVersion < WebVersion) { updateFound = true; } diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs index db01a3040b..cd19f1f820 100644 --- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLink.cs @@ -47,15 +47,15 @@ namespace ArdupilotMega /// /// storage for whole paramater list /// - public Hashtable param { get; set; } + public Hashtable param { get; set; } /// /// storage of a previous packet recevied of a specific type /// - public byte[][] packets { get; set; } + public byte[][] packets { get; set; } /// /// used to calc packets per second on any single message type - used for stream rate comparaison /// - public double[] packetspersecond { get; set; } + public double[] packetspersecond { get; set; } /// /// time last seen a packet of a type /// @@ -95,7 +95,7 @@ namespace ArdupilotMega /// /// time seen of last mavlink packet /// - public DateTime lastvalidpacket { get; set; } + public DateTime lastvalidpacket { get; set; } /// /// old log support /// @@ -112,7 +112,11 @@ namespace ArdupilotMega /// /// used as a snapshot of what is loaded on the ap atm. - derived from the stream /// - public PointLatLngAlt[] wps { get; set; } + public Dictionary wps = new Dictionary(); + /// + /// Store the guided mode wp location + /// + public mavlink_mission_item_t GuidedMode = new mavlink_mission_item_t(); /// /// turns on console packet display /// @@ -157,7 +161,6 @@ namespace ArdupilotMega this.oldlogformat = false; this.mavlinkversion = 0; this.aptype = 0; - this.wps = new PointLatLngAlt[200]; this.debugmavlink = false; this.logreadmode = false; this.lastlogread = DateTime.MinValue; @@ -547,7 +550,7 @@ namespace ArdupilotMega } catch { } // been getting errors from this. people must have it open twice. }*/ - } + } } public bool Write(string line) @@ -581,7 +584,7 @@ namespace ArdupilotMega MainV2.giveComport = true; - var req = new mavlink_param_set_t {target_system = sysid, target_component = compid}; + var req = new mavlink_param_set_t { target_system = sysid, target_component = compid }; byte[] temp = Encoding.ASCII.GetBytes(paramname); @@ -744,13 +747,13 @@ namespace ArdupilotMega MainV2.giveComport = false; if (packets > 0 && param_total == 1) { - throw new Exception("Timeout on read - getParamList\n"+packets+" Packets where received, but no paramater packets where received\n"); + throw new Exception("Timeout on read - getParamList\n" + packets + " Packets where received, but no paramater packets where received\n"); } if (packets == 0) { throw new Exception("Timeout on read - getParamList\nNo Packets where received\n"); } - + throw new Exception("Timeout on read - getParamList\nReceived: " + got.Count + " of " + param_total + " after 6 retrys\n\nPlease Check\n1. Link Speed\n2. Link Quality\n3. Hardware hasn't hung"); } @@ -761,7 +764,7 @@ namespace ArdupilotMega if (buffer.Length > 5) { packets++; - // stopwatch.Start(); + // stopwatch.Start(); if (buffer[5] == MAVLINK_MSG_ID_PARAM_VALUE) { restart = DateTime.Now; @@ -809,7 +812,7 @@ namespace ArdupilotMega this.frmProgressReporter.UpdateProgressAndStatus((got.Count * 100) / param_total, "Got param " + paramID); // we have them all - lets escape eq total = 176 index = 0-175 - if (par.param_index == (param_total -1)) + if (par.param_index == (param_total - 1)) break; } else @@ -817,8 +820,8 @@ namespace ArdupilotMega //Console.WriteLine(DateTime.Now + " PC paramlist " + buffer[5] + " want " + MAVLINK_MSG_ID_PARAM_VALUE + " btr " + BaseStream.BytesToRead); } //stopwatch.Stop(); - // Console.WriteLine("Time elapsed: {0}", stopwatch.Elapsed); - // Console.WriteLine(DateTime.Now.Millisecond + " gp4 " + BaseStream.BytesToRead); + // Console.WriteLine("Time elapsed: {0}", stopwatch.Elapsed); + // Console.WriteLine(DateTime.Now.Millisecond + " gp4 " + BaseStream.BytesToRead); } } while (got.Count < param_total); @@ -836,6 +839,70 @@ namespace ArdupilotMega return param; } + public float GetParam(string name) + { + return GetParam(name); + } + + public float GetParam(int index) + { + return GetParam("", index); + } + + /// + /// Get param by either index or name + /// + /// + /// + /// + internal float GetParam(string name = "", int index = -1) + { + if (name == "" && index == -1) + return 0; + + MainV2.giveComport = true; + byte[] buffer; + + mavlink_param_request_list_t req = new mavlink_param_request_list_t(); + req.target_system = sysid; + req.target_component = compid; + + generatePacket(MAVLINK_MSG_ID_PARAM_REQUEST_READ, req); + + DateTime start = DateTime.Now; + int retrys = 3; + + while (true) + { + if (!(start.AddMilliseconds(200) > DateTime.Now)) + { + if (retrys > 0) + { + log.Info("GetParam Retry " + retrys); + generatePacket(MAVLINK_MSG_ID_PARAM_REQUEST_READ, req); + start = DateTime.Now; + retrys--; + continue; + } + MainV2.giveComport = false; + throw new Exception("Timeout on read - GetParam"); + } + + buffer = readPacket(); + if (buffer.Length > 5) + { + if (buffer[5] == MAVLINK_MSG_ID_PARAM_VALUE) + { + MainV2.giveComport = false; + + mavlink_param_value_t par = buffer.ByteArrayToStructure(6); + + return par.param_value; + } + } + } + } + public static void modifyParamForDisplay(bool fromapm, string paramname, ref float value) { if (paramname.ToUpper().EndsWith("_IMAX") || paramname.ToUpper().EndsWith("ALT_HOLD_RTL") || paramname.ToUpper().EndsWith("APPROACH_ALT") || paramname.ToUpper().EndsWith("TRIM_ARSPD_CM") @@ -896,21 +963,12 @@ namespace ArdupilotMega public void setWPACK() { -#if MAVLINK10 MAVLink.mavlink_mission_ack_t req = new MAVLink.mavlink_mission_ack_t(); req.target_system = sysid; req.target_component = compid; req.type = 0; generatePacket(MAVLINK_MSG_ID_MISSION_ACK, req); -#else - MAVLink.mavlink_waypoint_ack_t req = new MAVLink.mavlink_waypoint_ack_t(); - req.target_system = sysid; - req.target_component = compid; - req.type = 0; - - generatePacket(MAVLINK_MSG_ID_WAYPOINT_ACK, req); -#endif } public bool setWPCurrent(ushort index) @@ -965,6 +1023,11 @@ namespace ArdupilotMega throw new NotImplementedException(); } + public bool doARM(bool armit) + { + return doCommand(MAV_CMD.COMPONENT_ARM_DISARM, armit ? 1 : 0, 0, 0, 0, 0, 0, 0); + } + public bool doCommand(MAV_CMD actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7) { @@ -976,6 +1039,11 @@ namespace ArdupilotMega req.target_system = sysid; req.target_component = compid; + if (actionid == MAV_CMD.COMPONENT_ARM_DISARM) + { + req.target_component = (byte)MAV_COMPONENT.MAV_COMP_ID_SYSTEM_CONTROL; + } + req.command = (ushort)actionid; req.param1 = p1; @@ -1691,7 +1759,7 @@ namespace ArdupilotMega /// public void setWPTotal(ushort wp_total) { -#if MAVLINK10 +#if MAVLINK10 MainV2.giveComport = true; mavlink_mission_count_t req = new mavlink_mission_count_t(); @@ -1736,6 +1804,9 @@ namespace ArdupilotMega param["WP_TOTAL"] = (float)wp_total - 1; if (param["CMD_TOTAL"] != null) param["CMD_TOTAL"] = (float)wp_total - 1; + + wps.Clear(); + MainV2.giveComport = false; return; } @@ -1809,14 +1880,10 @@ namespace ArdupilotMega /// wp no /// global or relative /// 0 = no , 2 = guided mode - public MAV_MISSION_RESULT setWP(Locationwp loc, ushort index, MAV_FRAME frame, byte current) + public MAV_MISSION_RESULT setWP(Locationwp loc, ushort index, MAV_FRAME frame, byte current = 0) { MainV2.giveComport = true; -#if MAVLINK10 mavlink_mission_item_t req = new mavlink_mission_item_t(); -#else - mavlink_waypoint_t req = new mavlink_waypoint_t(); -#endif req.target_system = sysid; req.target_component = compid; // MAVLINK_MSG_ID_MISSION_ITEM @@ -1835,68 +1902,14 @@ namespace ArdupilotMega req.param2 = loc.p2; req.param3 = loc.p3; req.param4 = loc.p4; - /* - if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) - { - switch (loc.id) - { // Switch to map APM command fields inot MAVLink command fields - case (byte)MAV_CMD.LOITER_TURNS: - case (byte)MAV_CMD.TAKEOFF: - req.param1 = loc.p1; - break; - case (byte)MAV_CMD.DO_SET_HOME: - req.param1 = loc.p1; - break; - case (byte)MAV_CMD.CONDITION_CHANGE_ALT: - req.param1 = loc.lat; - req.x = 0; - req.y = 0; - break; - - case (byte)MAV_CMD.LOITER_TIME: - req.param1 = loc.p1 * 10; // APM loiter time is in ten second increments - break; - - case (byte)MAV_CMD.CONDITION_DELAY: - case (byte)MAV_CMD.CONDITION_DISTANCE: - req.param1 = loc.lat; - break; - - case (byte)MAV_CMD.DO_JUMP: - req.param2 = loc.lat; - req.param1 = loc.p1; - break; - - case (byte)MAV_CMD.DO_REPEAT_SERVO: - req.param4 = loc.lng; - goto case (byte)MAV_CMD.DO_CHANGE_SPEED; - case (byte)MAV_CMD.DO_REPEAT_RELAY: - case (byte)MAV_CMD.DO_CHANGE_SPEED: - req.param3 = loc.lat; - req.param2 = loc.alt; - req.param1 = loc.p1; - break; - - case (byte)MAV_CMD.DO_SET_PARAMETER: - case (byte)MAV_CMD.DO_SET_RELAY: - case (byte)MAV_CMD.DO_SET_SERVO: - req.param2 = loc.alt; - req.param1 = loc.p1; - break; - } - } - */ req.seq = index; log.InfoFormat("setWP {6} frame {0} cmd {1} p1 {2} x {3} y {4} z {5}", req.frame, req.command, req.param1, req.x, req.y, req.z, index); // request -#if MAVLINK10 generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req); -#else - generatePacket(MAVLINK_MSG_ID_WAYPOINT, req); -#endif + DateTime start = DateTime.Now; int retrys = 10; @@ -1908,11 +1921,8 @@ namespace ArdupilotMega if (retrys > 0) { log.Info("setWP Retry " + retrys); -#if MAVLINK10 - generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req); -#else - generatePacket(MAVLINK_MSG_ID_WAYPOINT, req); -#endif + generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req); + start = DateTime.Now; retrys--; continue; @@ -1923,11 +1933,24 @@ namespace ArdupilotMega byte[] buffer = readPacket(); if (buffer.Length > 5) { -#if MAVLINK10 if (buffer[5] == MAVLINK_MSG_ID_MISSION_ACK) { var ans = buffer.ByteArrayToStructure(6); log.Info("set wp " + index + " ACK 47 : " + buffer[5] + " ans " + Enum.Parse(typeof(MAV_MISSION_RESULT), ans.type.ToString())); + + if (req.current == 2) + { + GuidedMode = req; + } + else if (req.current == 3) + { + + } + else + { + wps[req.seq] = req; + } + return (MAV_MISSION_RESULT)ans.type; } else if (buffer[5] == MAVLINK_MSG_ID_MISSION_REQUEST) @@ -1938,6 +1961,19 @@ namespace ArdupilotMega log.Info("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]); MainV2.giveComport = false; + if (req.current == 2) + { + GuidedMode = req; + } + else if (req.current == 3) + { + + } + else + { + wps[req.seq] = req; + } + return MAV_MISSION_RESULT.MAV_MISSION_ACCEPTED; } else @@ -1950,37 +1986,40 @@ namespace ArdupilotMega { //Console.WriteLine(DateTime.Now + " PC setwp " + buffer[5]); } -#else - if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_ACK) - { //mavlink_waypoint_request_t - log.Info("set wp " + index + " ACK 47 : " + buffer[5]); - break; - } - else if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST) - { - mavlink_waypoint_request_t ans = buffer.ByteArrayToStructure(6); - - if (ans.seq == (index + 1)) - { - log.Info("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]); - MainV2.giveComport = false; - break; - } - else - { - log.InfoFormat("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component); - //break; - } - } - else - { - //Console.WriteLine(DateTime.Now + " PC setwp " + buffer[5]); - } -#endif } } - // return MAV_MISSION_RESULT.MAV_MISSION_INVALID; + // return MAV_MISSION_RESULT.MAV_MISSION_INVALID; + } + + public void setNextWPTargetAlt(ushort wpno, float alt) + { + // get the existing wp + Locationwp current = getWP(wpno); + + mavlink_mission_write_partial_list_t req = new mavlink_mission_write_partial_list_t(); + req.target_system = sysid; + req.target_component = compid; + + req.start_index = (short)wpno; + req.end_index = (short)wpno; + + // change the alt + current.alt = alt; + + // send a request to update single point + generatePacket(MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, req); + Thread.Sleep(10); + generatePacket(MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, req); + + MAV_FRAME frame = (current.options & 0x1) == 0 ? MAV_FRAME.GLOBAL : MAV_FRAME.GLOBAL_RELATIVE_ALT; + + //send the point with new alt + setWP(current, wpno, MAV_FRAME.GLOBAL_RELATIVE_ALT, 0); + + // set the point as current to reload the modified command + setWPCurrent(wpno); + } public void setGuidedModeWP(Locationwp gotohere) @@ -1992,7 +2031,7 @@ namespace ArdupilotMega try { - gotohere.id =(byte)MAV_CMD.WAYPOINT; + gotohere.id = (byte)MAV_CMD.WAYPOINT; MAV_MISSION_RESULT ans = MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT, (byte)2); @@ -2004,6 +2043,24 @@ namespace ArdupilotMega MainV2.giveComport = false; } + public void setNewWPAlt(Locationwp gotohere) + { + MainV2.giveComport = true; + + try + { + gotohere.id = (byte)MAV_CMD.WAYPOINT; + + MAV_MISSION_RESULT ans = MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT, (byte)3); + + if (ans != MAV_MISSION_RESULT.MAV_MISSION_ACCEPTED) + throw new Exception("Alt Change Failed"); + } + catch (Exception ex) { log.Error(ex); } + + MainV2.giveComport = false; + } + public void setMountConfigure(MAV_MOUNT_MODE mountmode, bool stabroll, bool stabpitch, bool stabyaw) { mavlink_mount_configure_t req = new mavlink_mount_configure_t(); @@ -2046,7 +2103,6 @@ namespace ArdupilotMega public void setMode(string modein) { -#if MAVLINK10 try { MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t(); @@ -2057,38 +2113,15 @@ namespace ArdupilotMega } } catch { System.Windows.Forms.MessageBox.Show("Failed to change Modes"); } -#else - try - { - MAVLink.mavlink_set_nav_mode_t navmode = new MAVLink.mavlink_set_nav_mode_t(); - - MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t(); - - if (translateMode(modein, ref navmode, ref mode)) - { - generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_NAV_MODE, navmode); - System.Threading.Thread.Sleep(10); - generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode); - System.Threading.Thread.Sleep(10); - generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_NAV_MODE, navmode); - System.Threading.Thread.Sleep(10); - generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode); - } - } - catch { System.Windows.Forms.CustomMessageBox.Show("Failed to change Modes"); } - -#endif } public void setMode(mavlink_set_mode_t mode, MAV_MODE_FLAG base_mode = 0) { -#if MAVLINK10 mode.base_mode |= (byte)base_mode; generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode); System.Threading.Thread.Sleep(10); generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode); -#endif } /// @@ -2175,7 +2208,7 @@ namespace ArdupilotMega DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout); - // Console.WriteLine(DateTime.Now.Millisecond + " SR1a " + BaseStream.BytesToRead); + // Console.WriteLine(DateTime.Now.Millisecond + " SR1a " + BaseStream.BytesToRead); while (BaseStream.BytesToRead <= 0) { @@ -2240,7 +2273,7 @@ namespace ArdupilotMega int read = BaseStream.Read(buffer, 1, 5); count = read; if (rawlogfile != null && rawlogfile.BaseStream.CanWrite) - rawlogfile.Write(buffer,1,read); + rawlogfile.Write(buffer, 1, read); } // packet length @@ -2354,20 +2387,12 @@ namespace ArdupilotMega else { log.InfoFormat("Mavlink Bad Packet (Len Fail) len {0} pkno {1}", buffer.Length, buffer[5]); -#if MAVLINK10 - if (buffer.Length == 11 && buffer[0] == 'U' && buffer[5] == 0){ - string message ="Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n"; - System.Windows.Forms.CustomMessageBox.Show(message); - throw new Exception(message); - } -#else - if (buffer.Length == 17 && buffer[0] == 254 && buffer[5] == 0) + if (buffer.Length == 11 && buffer[0] == 'U' && buffer[5] == 0) { - string message = "Mavlink 1.0 Heartbeat, Please Upgrade your Mission Planner, This planner is for Mavlink 0.9\n\n"; + string message = "Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n"; System.Windows.Forms.CustomMessageBox.Show(message); throw new Exception(message); } -#endif return new byte[0]; } } @@ -2393,7 +2418,7 @@ namespace ArdupilotMega } else { - + byte packetSeqNo = buffer[2]; int expectedPacketSeqNo = ((recvpacketcount + 1) % 0x100); @@ -2428,7 +2453,7 @@ namespace ArdupilotMega recvpacketcount = packetSeqNo; } WhenPacketReceived.OnNext(1); - // Console.WriteLine(DateTime.Now.Millisecond); + // Console.WriteLine(DateTime.Now.Millisecond); } //MAVLINK_MSG_ID_GPS_STATUS @@ -2481,10 +2506,11 @@ namespace ArdupilotMega logfile.Write(datearray, 0, datearray.Length); logfile.Write(buffer, 0, buffer.Length); - if (buffer[5] == 0) {// flush on heartbeat - 1 seconds + if (buffer[5] == 0) + {// flush on heartbeat - 1 seconds logfile.BaseStream.Flush(); - rawlogfile.BaseStream.Flush(); - } + rawlogfile.BaseStream.Flush(); + } } } @@ -2498,7 +2524,7 @@ namespace ArdupilotMega // Console.Write((DateTime.Now - start).TotalMilliseconds.ToString("00.000") + "\t" + temp.Length + " \r"); - // Console.WriteLine(DateTime.Now.Millisecond + " SR4 " + BaseStream.BytesToRead); + // Console.WriteLine(DateTime.Now.Millisecond + " SR4 " + BaseStream.BytesToRead); return buffer; } @@ -2509,32 +2535,28 @@ namespace ArdupilotMega /// packet void getWPsfromstream(ref byte[] buffer) { -#if MAVLINK10 if (buffer[5] == MAVLINK_MSG_ID_MISSION_COUNT) { // clear old - wps = new PointLatLngAlt[wps.Length]; + wps.Clear(); + //new PointLatLngAlt[wps.Length]; } if (buffer[5] == MAVLink.MAVLINK_MSG_ID_MISSION_ITEM) { mavlink_mission_item_t wp = buffer.ByteArrayToStructure(6); -#else - if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_COUNT) - { - // clear old - wps = new PointLatLngAlt[wps.Length]; - } + if (wp.current == 2) + { + // guide mode wp + GuidedMode = wp; + } + else + { + wps[wp.seq] = wp; + } - if (buffer[5] == MAVLink.MAVLINK_MSG_ID_WAYPOINT) - { - mavlink_waypoint_t wp = buffer.ByteArrayToStructure(6); - -#endif - wps[wp.seq] = new PointLatLngAlt(wp.x, wp.y, wp.z, wp.seq.ToString()); - - Console.WriteLine("WP # {7} cmd {8} p1 {0} p2 {1} p3 {2} p4 {3} x {4} y {5} z {6}",wp.param1,wp.param2,wp.param3,wp.param4,wp.x,wp.y,wp.z,wp.seq,wp.command); + Console.WriteLine("WP # {7} cmd {8} p1 {0} p2 {1} p3 {2} p4 {3} x {4} y {5} z {6}", wp.param1, wp.param2, wp.param3, wp.param4, wp.x, wp.y, wp.z, wp.seq, wp.command); } } @@ -2715,7 +2737,8 @@ namespace ArdupilotMega } // set ap type for log file playback - if (temp[5] == 0) { + if (temp[5] == 0) + { mavlink_heartbeat_t hb = temp.ByteArrayToStructure(6); mavlinkversion = hb.mavlink_version; @@ -2726,9 +2749,6 @@ namespace ArdupilotMega return temp; } - -#if MAVLINK10 - public static bool translateMode(string modein, ref MAVLink.mavlink_set_mode_t mode) { //MAVLink09.mavlink_set_mode_t mode = new MAVLink09.mavlink_set_mode_t(); @@ -2752,7 +2772,7 @@ namespace ArdupilotMega mode.custom_mode = (uint)EnumTranslator.GetValue(modein); break; default: - MessageBox.Show("No Mode Changed " + modein); + MessageBox.Show("No Mode Changed " + modein); return false; } } @@ -2772,7 +2792,7 @@ namespace ArdupilotMega mode.custom_mode = (uint)EnumTranslator.GetValue(modein); break; default: - MessageBox.Show("No Mode Changed " + modein); + MessageBox.Show("No Mode Changed " + modein); return false; } } @@ -2781,136 +2801,7 @@ namespace ArdupilotMega return true; } - -#else - public static bool translateMode(string modein, ref MAVLink.mavlink_set_nav_mode_t navmode, ref MAVLink.mavlink_set_mode_t mode) - { - //MAVLink.mavlink_set_nav_mode_t navmode = new MAVLink.mavlink_set_nav_mode_t(); - navmode.target = MainV2.comPort.sysid; - navmode.nav_mode = 255; - - //MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t(); - mode.target = MainV2.comPort.sysid; - - try - { - if (Common.getModes() == typeof(Common.apmmodes)) - { - switch (EnumTranslator.GetValue(modein)) - { - case (int)Common.apmmodes.MANUAL: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_MANUAL; - break; - case (int)Common.apmmodes.GUIDED: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_GUIDED; - break; - case (int)Common.apmmodes.STABILIZE: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST1; - break; - // AUTO MODES - case (int)Common.apmmodes.AUTO: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_WAYPOINT; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - case (int)Common.apmmodes.RTL: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_RETURNING; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - case (int)Common.apmmodes.LOITER: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_LOITER; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - // FBW - case (int)Common.apmmodes.FLY_BY_WIRE_A: - navmode.nav_mode = (byte)1; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2; - break; - case (int)Common.apmmodes.FLY_BY_WIRE_B: - navmode.nav_mode = (byte)2; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2; - break; - default: - CustomMessageBox.Show("No Mode Changed " + modein); - return false; - } - } - else if (Common.getModes() == typeof(Common.aprovermodes)) - { - switch (EnumTranslator.GetValue(modein)) - { - case (int)Common.aprovermodes.MANUAL: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_MANUAL; - break; - case (int)Common.aprovermodes.GUIDED: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_GUIDED; - break; - case (int)Common.aprovermodes.LEARNING: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST1; - break; - // AUTO MODES - case (int)Common.aprovermodes.AUTO: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_WAYPOINT; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - case (int)Common.aprovermodes.RTL: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_RETURNING; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - case (int)Common.aprovermodes.LOITER: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_LOITER; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - // FBW - case (int)Common.aprovermodes.FLY_BY_WIRE_A: - navmode.nav_mode = (byte)1; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2; - break; - case (int)Common.aprovermodes.FLY_BY_WIRE_B: - navmode.nav_mode = (byte)2; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2; - break; - default: - CustomMessageBox.Show("No Mode Changed " + modein); - return false; - } - } - else if (Common.getModes() == typeof(Common.ac2modes)) - { - switch (EnumTranslator.GetValue(modein)) - { - case (int)Common.ac2modes.GUIDED: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_GUIDED; - break; - case (int)Common.ac2modes.STABILIZE: - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_MANUAL; - break; - // AUTO MODES - case (int)Common.ac2modes.AUTO: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_WAYPOINT; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - case (int)Common.ac2modes.RTL: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_RETURNING; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - case (int)Common.ac2modes.LOITER: - navmode.nav_mode = (byte)MAVLink.MAV_NAV.MAV_NAV_LOITER; - mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO; - break; - default: - CustomMessageBox.Show("No Mode Changed " + modein); - return false; - } - } - } - catch { System.Windows.Forms.CustomMessageBox.Show("Failed to find Mode"); return false; } - - return true; - } -#endif - -#if MAVLINK10 public void setAPType() { switch (aptype) @@ -2928,24 +2819,6 @@ namespace ArdupilotMega break; } } -#else - public void setAPType() - { - switch (aptype) - { - case MAVLink.MAV_TYPE.MAV_FIXED_WING: - MainV2.cs.firmware = MainV2.Firmwares.ArduPlane; - break; - case MAVLink.MAV_TYPE.MAV_QUADROTOR: - MainV2.cs.firmware = MainV2.Firmwares.ArduCopter2; - break; - case MAVLink.MAV_TYPE.MAV_GROUND: - MainV2.cs.firmware = MainV2.Firmwares.ArduRover; - break; - default: - break; - } - } -#endif + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLinkTypes.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLinkTypes.cs index c535ea00ce..28fe12993e 100644 --- a/Tools/ArdupilotMegaPlanner/Mavlink/MAVLinkTypes.cs +++ b/Tools/ArdupilotMegaPlanner/Mavlink/MAVLinkTypes.cs @@ -5,7 +5,6 @@ using System.Runtime.InteropServices; namespace ArdupilotMega { -#if MAVLINK10 partial class MAVLink { public const string MAVLINK_BUILD_DATE = "Sat Aug 18 07:50:27 2012"; @@ -22,2528 +21,2527 @@ namespace ArdupilotMega public const bool MAVLINK_ALIGNED_FIELDS = (1 == 1); public const byte MAVLINK_CRC_EXTRA = 1; - + public const bool MAVLINK_NEED_BYTE_SWAP = (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN); - - public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}; - public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}; + public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] { 9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0 }; - public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_system_time_t ), null, typeof( mavlink_ping_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, null, null, typeof( mavlink_set_mode_t ), null, null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), typeof( mavlink_gps_raw_int_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_attitude_quaternion_t ), typeof( mavlink_local_position_ned_t ), typeof( mavlink_global_position_int_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_mission_request_partial_list_t ), typeof( mavlink_mission_write_partial_list_t ), typeof( mavlink_mission_item_t ), typeof( mavlink_mission_request_t ), typeof( mavlink_mission_set_current_t ), typeof( mavlink_mission_current_t ), typeof( mavlink_mission_request_list_t ), typeof( mavlink_mission_count_t ), typeof( mavlink_mission_clear_all_t ), typeof( mavlink_mission_item_reached_t ), typeof( mavlink_mission_ack_t ), typeof( mavlink_set_gps_global_origin_t ), typeof( mavlink_gps_global_origin_t ), typeof( mavlink_set_local_position_setpoint_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_global_position_setpoint_int_t ), typeof( mavlink_set_global_position_setpoint_int_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), typeof( mavlink_set_quad_motors_setpoint_t ), typeof( mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t ), typeof( mavlink_nav_controller_output_t ), typeof( mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t ), typeof( mavlink_state_correction_t ), null, typeof( mavlink_request_data_stream_t ), typeof( mavlink_data_stream_t ), null, typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, null, typeof( mavlink_vfr_hud_t ), null, typeof( mavlink_command_long_t ), typeof( mavlink_command_ack_t ), null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_local_position_ned_system_global_offset_t ), typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_hil_rc_inputs_raw_t ), null, null, null, null, null, null, null, typeof( mavlink_optical_flow_t ), typeof( mavlink_global_vision_position_estimate_t ), typeof( mavlink_vision_position_estimate_t ), typeof( mavlink_vision_speed_estimate_t ), typeof( mavlink_vicon_position_estimate_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_sensor_offsets_t ), typeof( mavlink_set_mag_offsets_t ), typeof( mavlink_meminfo_t ), typeof( mavlink_ap_adc_t ), typeof( mavlink_digicam_configure_t ), typeof( mavlink_digicam_control_t ), typeof( mavlink_mount_configure_t ), typeof( mavlink_mount_control_t ), typeof( mavlink_mount_status_t ), null, typeof( mavlink_fence_point_t ), typeof( mavlink_fence_fetch_point_t ), typeof( mavlink_fence_status_t ), typeof( mavlink_ahrs_t ), typeof( mavlink_simstate_t ), typeof( mavlink_hwstatus_t ), typeof( mavlink_radio_t ), typeof( mavlink_limits_status_t ), typeof( mavlink_wind_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_memory_vect_t ), typeof( mavlink_debug_vect_t ), typeof( mavlink_named_value_float_t ), typeof( mavlink_named_value_int_t ), typeof( mavlink_statustext_t ), typeof( mavlink_debug_t ), null}; + public byte[] MAVLINK_MESSAGE_CRCS = new byte[] { 50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0 }; + + public Type[] MAVLINK_MESSAGE_INFO = new Type[] { typeof(mavlink_heartbeat_t), typeof(mavlink_sys_status_t), typeof(mavlink_system_time_t), null, typeof(mavlink_ping_t), typeof(mavlink_change_operator_control_t), typeof(mavlink_change_operator_control_ack_t), typeof(mavlink_auth_key_t), null, null, null, typeof(mavlink_set_mode_t), null, null, null, null, null, null, null, null, typeof(mavlink_param_request_read_t), typeof(mavlink_param_request_list_t), typeof(mavlink_param_value_t), typeof(mavlink_param_set_t), typeof(mavlink_gps_raw_int_t), typeof(mavlink_gps_status_t), typeof(mavlink_scaled_imu_t), typeof(mavlink_raw_imu_t), typeof(mavlink_raw_pressure_t), typeof(mavlink_scaled_pressure_t), typeof(mavlink_attitude_t), typeof(mavlink_attitude_quaternion_t), typeof(mavlink_local_position_ned_t), typeof(mavlink_global_position_int_t), typeof(mavlink_rc_channels_scaled_t), typeof(mavlink_rc_channels_raw_t), typeof(mavlink_servo_output_raw_t), typeof(mavlink_mission_request_partial_list_t), typeof(mavlink_mission_write_partial_list_t), typeof(mavlink_mission_item_t), typeof(mavlink_mission_request_t), typeof(mavlink_mission_set_current_t), typeof(mavlink_mission_current_t), typeof(mavlink_mission_request_list_t), typeof(mavlink_mission_count_t), typeof(mavlink_mission_clear_all_t), typeof(mavlink_mission_item_reached_t), typeof(mavlink_mission_ack_t), typeof(mavlink_set_gps_global_origin_t), typeof(mavlink_gps_global_origin_t), typeof(mavlink_set_local_position_setpoint_t), typeof(mavlink_local_position_setpoint_t), typeof(mavlink_global_position_setpoint_int_t), typeof(mavlink_set_global_position_setpoint_int_t), typeof(mavlink_safety_set_allowed_area_t), typeof(mavlink_safety_allowed_area_t), typeof(mavlink_set_roll_pitch_yaw_thrust_t), typeof(mavlink_set_roll_pitch_yaw_speed_thrust_t), typeof(mavlink_roll_pitch_yaw_thrust_setpoint_t), typeof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t), typeof(mavlink_set_quad_motors_setpoint_t), typeof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t), typeof(mavlink_nav_controller_output_t), typeof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t), typeof(mavlink_state_correction_t), null, typeof(mavlink_request_data_stream_t), typeof(mavlink_data_stream_t), null, typeof(mavlink_manual_control_t), typeof(mavlink_rc_channels_override_t), null, null, null, typeof(mavlink_vfr_hud_t), null, typeof(mavlink_command_long_t), typeof(mavlink_command_ack_t), null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_local_position_ned_system_global_offset_t), typeof(mavlink_hil_state_t), typeof(mavlink_hil_controls_t), typeof(mavlink_hil_rc_inputs_raw_t), null, null, null, null, null, null, null, typeof(mavlink_optical_flow_t), typeof(mavlink_global_vision_position_estimate_t), typeof(mavlink_vision_position_estimate_t), typeof(mavlink_vision_speed_estimate_t), typeof(mavlink_vicon_position_estimate_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_sensor_offsets_t), typeof(mavlink_set_mag_offsets_t), typeof(mavlink_meminfo_t), typeof(mavlink_ap_adc_t), typeof(mavlink_digicam_configure_t), typeof(mavlink_digicam_control_t), typeof(mavlink_mount_configure_t), typeof(mavlink_mount_control_t), typeof(mavlink_mount_status_t), null, typeof(mavlink_fence_point_t), typeof(mavlink_fence_fetch_point_t), typeof(mavlink_fence_status_t), typeof(mavlink_ahrs_t), typeof(mavlink_simstate_t), typeof(mavlink_hwstatus_t), typeof(mavlink_radio_t), typeof(mavlink_limits_status_t), typeof(mavlink_wind_t), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof(mavlink_memory_vect_t), typeof(mavlink_debug_vect_t), typeof(mavlink_named_value_float_t), typeof(mavlink_named_value_int_t), typeof(mavlink_statustext_t), typeof(mavlink_debug_t), null }; public const byte MAVLINK_VERSION = 2; - - + + /** @brief Enumeration of possible mount operation modes */ public enum MAV_MOUNT_MODE { - /// Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | - RETRACT=0, - /// Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | - NEUTRAL=1, - /// Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | - MAVLINK_TARGETING=2, - /// Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | - RC_TARGETING=3, - /// Load neutral position and start to point to Lat,Lon,Alt | - GPS_POINT=4, - /// | - ENUM_END=5, - + /// Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | + RETRACT = 0, + /// Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | + NEUTRAL = 1, + /// Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | + MAVLINK_TARGETING = 2, + /// Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | + RC_TARGETING = 3, + /// Load neutral position and start to point to Lat,Lon,Alt | + GPS_POINT = 4, + /// | + ENUM_END = 5, + }; - + /** @brief */ public enum MAV_CMD { - /// Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| - WAYPOINT=16, - /// Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| - LOITER_UNLIM=17, - /// Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| - LOITER_TURNS=18, - /// Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| - LOITER_TIME=19, - /// Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| - RETURN_TO_LAUNCH=20, - /// Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| - LAND=21, - /// Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| - TAKEOFF=22, - /// Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| - ROI=80, - /// Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| - PATHPLANNING=81, - /// NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| - LAST=95, - /// Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| - CONDITION_DELAY=112, - /// Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| - CONDITION_CHANGE_ALT=113, - /// Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| - CONDITION_DISTANCE=114, - /// Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| - CONDITION_YAW=115, - /// NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| - CONDITION_LAST=159, - /// Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| - DO_SET_MODE=176, - /// Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| - DO_JUMP=177, - /// Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| - DO_CHANGE_SPEED=178, - /// Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| - DO_SET_HOME=179, - /// Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| - DO_SET_PARAMETER=180, - /// Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| - DO_SET_RELAY=181, - /// Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| - DO_REPEAT_RELAY=182, - /// Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| - DO_SET_SERVO=183, - /// Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| - DO_REPEAT_SERVO=184, - /// Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| - DO_CONTROL_VIDEO=200, - /// Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| - DO_DIGICAM_CONFIGURE=202, - /// Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| - DO_DIGICAM_CONTROL=203, - /// Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| - DO_MOUNT_CONFIGURE=204, - /// Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| - DO_MOUNT_CONTROL=205, - /// NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| - DO_LAST=240, - /// Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| - PREFLIGHT_CALIBRATION=241, - /// Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| - PREFLIGHT_SET_SENSOR_OFFSETS=242, - /// Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| - PREFLIGHT_STORAGE=245, - /// Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| - PREFLIGHT_REBOOT_SHUTDOWN=246, - /// Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| - OVERRIDE_GOTO=252, - /// 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)| - MISSION_START=300, - /// Arms / Disarms a component |1 to arm, 0 to disarm| - COMPONENT_ARM_DISARM=400, - /// | - ENUM_END=401, - + /// Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| + WAYPOINT = 16, + /// Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| + LOITER_UNLIM = 17, + /// Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| + LOITER_TURNS = 18, + /// Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| + LOITER_TIME = 19, + /// Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| + RETURN_TO_LAUNCH = 20, + /// Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| + LAND = 21, + /// Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| + TAKEOFF = 22, + /// Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| + ROI = 80, + /// Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| + PATHPLANNING = 81, + /// NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| + LAST = 95, + /// Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| + CONDITION_DELAY = 112, + /// Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| + CONDITION_CHANGE_ALT = 113, + /// Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| + CONDITION_DISTANCE = 114, + /// Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| + CONDITION_YAW = 115, + /// NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| + CONDITION_LAST = 159, + /// Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| + DO_SET_MODE = 176, + /// Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| + DO_JUMP = 177, + /// Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| + DO_CHANGE_SPEED = 178, + /// Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| + DO_SET_HOME = 179, + /// Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| + DO_SET_PARAMETER = 180, + /// Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| + DO_SET_RELAY = 181, + /// Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| + DO_REPEAT_RELAY = 182, + /// Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| + DO_SET_SERVO = 183, + /// Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| + DO_REPEAT_SERVO = 184, + /// Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| + DO_CONTROL_VIDEO = 200, + /// Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| + DO_DIGICAM_CONFIGURE = 202, + /// Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| + DO_DIGICAM_CONTROL = 203, + /// Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| + DO_MOUNT_CONFIGURE = 204, + /// Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| + DO_MOUNT_CONTROL = 205, + /// NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| + DO_LAST = 240, + /// Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| + PREFLIGHT_CALIBRATION = 241, + /// Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| + PREFLIGHT_SET_SENSOR_OFFSETS = 242, + /// Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| + PREFLIGHT_STORAGE = 245, + /// Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| + PREFLIGHT_REBOOT_SHUTDOWN = 246, + /// Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| + OVERRIDE_GOTO = 252, + /// 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)| + MISSION_START = 300, + /// Arms / Disarms a component |1 to arm, 0 to disarm| + COMPONENT_ARM_DISARM = 400, + /// | + ENUM_END = 401, + }; - + /** @brief */ public enum FENCE_ACTION { - /// Disable fenced mode | - NONE=0, - /// Switched to guided mode to return point (fence point 0) | - GUIDED=1, - /// Report fence breach, but don't take action | - REPORT=2, - /// | - ENUM_END=3, - + /// Disable fenced mode | + NONE = 0, + /// Switched to guided mode to return point (fence point 0) | + GUIDED = 1, + /// Report fence breach, but don't take action | + REPORT = 2, + /// | + ENUM_END = 3, + }; - + /** @brief */ public enum FENCE_BREACH { - /// No last fence breach | - NONE=0, - /// Breached minimum altitude | - MINALT=1, - /// Breached minimum altitude | - MAXALT=2, - /// Breached fence boundary | - BOUNDARY=3, - /// | - ENUM_END=4, - + /// No last fence breach | + NONE = 0, + /// Breached minimum altitude | + MINALT = 1, + /// Breached minimum altitude | + MAXALT = 2, + /// Breached fence boundary | + BOUNDARY = 3, + /// | + ENUM_END = 4, + }; - + /** @brief */ public enum LIMITS_STATE { - /// pre-initialization | - LIMITS_INIT=0, - /// disabled | - LIMITS_DISABLED=1, - /// checking limits | - LIMITS_ENABLED=2, - /// a limit has been breached | - LIMITS_TRIGGERED=3, - /// taking action eg. RTL | - LIMITS_RECOVERING=4, - /// we're no longer in breach of a limit | - LIMITS_RECOVERED=5, - /// | - ENUM_END=6, - + /// pre-initialization | + LIMITS_INIT = 0, + /// disabled | + LIMITS_DISABLED = 1, + /// checking limits | + LIMITS_ENABLED = 2, + /// a limit has been breached | + LIMITS_TRIGGERED = 3, + /// taking action eg. RTL | + LIMITS_RECOVERING = 4, + /// we're no longer in breach of a limit | + LIMITS_RECOVERED = 5, + /// | + ENUM_END = 6, + }; - + /** @brief */ public enum LIMIT_MODULE { - /// pre-initialization | - LIMIT_GPSLOCK=1, - /// disabled | - LIMIT_GEOFENCE=2, - /// checking limits | - LIMIT_ALTITUDE=4, - /// | - ENUM_END=5, - + /// pre-initialization | + LIMIT_GPSLOCK = 1, + /// disabled | + LIMIT_GEOFENCE = 2, + /// checking limits | + LIMIT_ALTITUDE = 4, + /// | + ENUM_END = 5, + }; - - - + + + /** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ public enum MAV_AUTOPILOT { - /// Generic autopilot, full support for everything | - GENERIC=0, - /// PIXHAWK autopilot, http://pixhawk.ethz.ch | - PIXHAWK=1, - /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu | - SLUGS=2, - /// ArduPilotMega / ArduCopter, http://diydrones.com | - ARDUPILOTMEGA=3, - /// OpenPilot, http://openpilot.org | - OPENPILOT=4, - /// Generic autopilot only supporting simple waypoints | - GENERIC_WAYPOINTS_ONLY=5, - /// Generic autopilot supporting waypoints and other simple navigation commands | - GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, - /// Generic autopilot supporting the full mission command set | - GENERIC_MISSION_FULL=7, - /// No valid autopilot, e.g. a GCS or other MAVLink component | - INVALID=8, - /// PPZ UAV - http://nongnu.org/paparazzi | - PPZ=9, - /// UAV Dev Board | - UDB=10, - /// FlexiPilot | - FP=11, - /// | - ENUM_END=12, - + /// Generic autopilot, full support for everything | + GENERIC = 0, + /// PIXHAWK autopilot, http://pixhawk.ethz.ch | + PIXHAWK = 1, + /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu | + SLUGS = 2, + /// ArduPilotMega / ArduCopter, http://diydrones.com | + ARDUPILOTMEGA = 3, + /// OpenPilot, http://openpilot.org | + OPENPILOT = 4, + /// Generic autopilot only supporting simple waypoints | + GENERIC_WAYPOINTS_ONLY = 5, + /// Generic autopilot supporting waypoints and other simple navigation commands | + GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6, + /// Generic autopilot supporting the full mission command set | + GENERIC_MISSION_FULL = 7, + /// No valid autopilot, e.g. a GCS or other MAVLink component | + INVALID = 8, + /// PPZ UAV - http://nongnu.org/paparazzi | + PPZ = 9, + /// UAV Dev Board | + UDB = 10, + /// FlexiPilot | + FP = 11, + /// | + ENUM_END = 12, + }; - + /** @brief */ public enum MAV_TYPE { - /// Generic micro air vehicle. | - GENERIC=0, - /// Fixed wing aircraft. | - FIXED_WING=1, - /// Quadrotor | - QUADROTOR=2, - /// Coaxial helicopter | - COAXIAL=3, - /// Normal helicopter with tail rotor. | - HELICOPTER=4, - /// Ground installation | - ANTENNA_TRACKER=5, - /// Operator control unit / ground control station | - GCS=6, - /// Airship, controlled | - AIRSHIP=7, - /// Free balloon, uncontrolled | - FREE_BALLOON=8, - /// Rocket | - ROCKET=9, - /// Ground rover | - GROUND_ROVER=10, - /// Surface vessel, boat, ship | - SURFACE_BOAT=11, - /// Submarine | - SUBMARINE=12, - /// Hexarotor | - HEXAROTOR=13, - /// Octorotor | - OCTOROTOR=14, - /// Octorotor | - TRICOPTER=15, - /// Flapping wing | - FLAPPING_WING=16, - /// Flapping wing | - KITE=17, - /// | - ENUM_END=18, - + /// Generic micro air vehicle. | + GENERIC = 0, + /// Fixed wing aircraft. | + FIXED_WING = 1, + /// Quadrotor | + QUADROTOR = 2, + /// Coaxial helicopter | + COAXIAL = 3, + /// Normal helicopter with tail rotor. | + HELICOPTER = 4, + /// Ground installation | + ANTENNA_TRACKER = 5, + /// Operator control unit / ground control station | + GCS = 6, + /// Airship, controlled | + AIRSHIP = 7, + /// Free balloon, uncontrolled | + FREE_BALLOON = 8, + /// Rocket | + ROCKET = 9, + /// Ground rover | + GROUND_ROVER = 10, + /// Surface vessel, boat, ship | + SURFACE_BOAT = 11, + /// Submarine | + SUBMARINE = 12, + /// Hexarotor | + HEXAROTOR = 13, + /// Octorotor | + OCTOROTOR = 14, + /// Octorotor | + TRICOPTER = 15, + /// Flapping wing | + FLAPPING_WING = 16, + /// Flapping wing | + KITE = 17, + /// | + ENUM_END = 18, + }; - + /** @brief These flags encode the MAV mode. */ public enum MAV_MODE_FLAG { - /// 0b00000001 Reserved for future use. | - CUSTOM_MODE_ENABLED=1, - /// 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | - TEST_ENABLED=2, - /// 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | - AUTO_ENABLED=4, - /// 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | - GUIDED_ENABLED=8, - /// 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | - STABILIZE_ENABLED=16, - /// 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | - HIL_ENABLED=32, - /// 0b01000000 remote control input is enabled. | - MANUAL_INPUT_ENABLED=64, - /// 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | - SAFETY_ARMED=128, - /// | - ENUM_END=129, - + /// 0b00000001 Reserved for future use. | + CUSTOM_MODE_ENABLED = 1, + /// 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | + TEST_ENABLED = 2, + /// 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | + AUTO_ENABLED = 4, + /// 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | + GUIDED_ENABLED = 8, + /// 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | + STABILIZE_ENABLED = 16, + /// 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | + HIL_ENABLED = 32, + /// 0b01000000 remote control input is enabled. | + MANUAL_INPUT_ENABLED = 64, + /// 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | + SAFETY_ARMED = 128, + /// | + ENUM_END = 129, + }; - + /** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ public enum MAV_MODE_FLAG_DECODE_POSITION { - /// Eighth bit: 00000001 | - CUSTOM_MODE=1, - /// Seventh bit: 00000010 | - TEST=2, - /// Sixt bit: 00000100 | - AUTO=4, - /// Fifth bit: 00001000 | - GUIDED=8, - /// Fourth bit: 00010000 | - STABILIZE=16, - /// Third bit: 00100000 | - HIL=32, - /// Second bit: 01000000 | - MANUAL=64, - /// First bit: 10000000 | - SAFETY=128, - /// | - ENUM_END=129, - + /// Eighth bit: 00000001 | + CUSTOM_MODE = 1, + /// Seventh bit: 00000010 | + TEST = 2, + /// Sixt bit: 00000100 | + AUTO = 4, + /// Fifth bit: 00001000 | + GUIDED = 8, + /// Fourth bit: 00010000 | + STABILIZE = 16, + /// Third bit: 00100000 | + HIL = 32, + /// Second bit: 01000000 | + MANUAL = 64, + /// First bit: 10000000 | + SAFETY = 128, + /// | + ENUM_END = 129, + }; - + /** @brief Override command, pauses current mission execution and moves immediately to a position */ public enum MAV_GOTO { - /// Hold at the current position. | - DO_HOLD=0, - /// Continue with the next item in mission execution. | - DO_CONTINUE=1, - /// Hold at the current position of the system | - HOLD_AT_CURRENT_POSITION=2, - /// Hold at the position specified in the parameters of the DO_HOLD action | - HOLD_AT_SPECIFIED_POSITION=3, - /// | - ENUM_END=4, - + /// Hold at the current position. | + DO_HOLD = 0, + /// Continue with the next item in mission execution. | + DO_CONTINUE = 1, + /// Hold at the current position of the system | + HOLD_AT_CURRENT_POSITION = 2, + /// Hold at the position specified in the parameters of the DO_HOLD action | + HOLD_AT_SPECIFIED_POSITION = 3, + /// | + ENUM_END = 4, + }; - + /** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ public enum MAV_MODE { - /// System is not ready to fly, booting, calibrating, etc. No flag is set. | - PREFLIGHT=0, - /// System is allowed to be active, under manual (RC) control, no stabilization | - MANUAL_DISARMED=64, - /// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | - TEST_DISARMED=66, - /// System is allowed to be active, under assisted RC control. | - STABILIZE_DISARMED=80, - /// System is allowed to be active, under autonomous control, manual setpoint | - GUIDED_DISARMED=88, - /// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | - AUTO_DISARMED=92, - /// System is allowed to be active, under manual (RC) control, no stabilization | - MANUAL_ARMED=192, - /// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | - TEST_ARMED=194, - /// System is allowed to be active, under assisted RC control. | - STABILIZE_ARMED=208, - /// System is allowed to be active, under autonomous control, manual setpoint | - GUIDED_ARMED=216, - /// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | - AUTO_ARMED=220, - /// | - ENUM_END=221, - + /// System is not ready to fly, booting, calibrating, etc. No flag is set. | + PREFLIGHT = 0, + /// System is allowed to be active, under manual (RC) control, no stabilization | + MANUAL_DISARMED = 64, + /// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | + TEST_DISARMED = 66, + /// System is allowed to be active, under assisted RC control. | + STABILIZE_DISARMED = 80, + /// System is allowed to be active, under autonomous control, manual setpoint | + GUIDED_DISARMED = 88, + /// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | + AUTO_DISARMED = 92, + /// System is allowed to be active, under manual (RC) control, no stabilization | + MANUAL_ARMED = 192, + /// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | + TEST_ARMED = 194, + /// System is allowed to be active, under assisted RC control. | + STABILIZE_ARMED = 208, + /// System is allowed to be active, under autonomous control, manual setpoint | + GUIDED_ARMED = 216, + /// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | + AUTO_ARMED = 220, + /// | + ENUM_END = 221, + }; - + /** @brief */ public enum MAV_STATE { - /// Uninitialized system, state is unknown. | - UNINIT=0, - /// System is booting up. | - BOOT=1, - /// System is calibrating and not flight-ready. | - CALIBRATING=2, - /// System is grounded and on standby. It can be launched any time. | - STANDBY=3, - /// System is active and might be already airborne. Motors are engaged. | - ACTIVE=4, - /// System is in a non-normal flight mode. It can however still navigate. | - CRITICAL=5, - /// System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | - EMERGENCY=6, - /// System just initialized its power-down sequence, will shut down now. | - POWEROFF=7, - /// | - ENUM_END=8, - + /// Uninitialized system, state is unknown. | + UNINIT = 0, + /// System is booting up. | + BOOT = 1, + /// System is calibrating and not flight-ready. | + CALIBRATING = 2, + /// System is grounded and on standby. It can be launched any time. | + STANDBY = 3, + /// System is active and might be already airborne. Motors are engaged. | + ACTIVE = 4, + /// System is in a non-normal flight mode. It can however still navigate. | + CRITICAL = 5, + /// System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | + EMERGENCY = 6, + /// System just initialized its power-down sequence, will shut down now. | + POWEROFF = 7, + /// | + ENUM_END = 8, + }; - + /** @brief */ public enum MAV_COMPONENT { - /// | - MAV_COMP_ID_ALL=0, - /// | - MAV_COMP_ID_CAMERA=100, - /// | - MAV_COMP_ID_SERVO1=140, - /// | - MAV_COMP_ID_SERVO2=141, - /// | - MAV_COMP_ID_SERVO3=142, - /// | - MAV_COMP_ID_SERVO4=143, - /// | - MAV_COMP_ID_SERVO5=144, - /// | - MAV_COMP_ID_SERVO6=145, - /// | - MAV_COMP_ID_SERVO7=146, - /// | - MAV_COMP_ID_SERVO8=147, - /// | - MAV_COMP_ID_SERVO9=148, - /// | - MAV_COMP_ID_SERVO10=149, - /// | - MAV_COMP_ID_SERVO11=150, - /// | - MAV_COMP_ID_SERVO12=151, - /// | - MAV_COMP_ID_SERVO13=152, - /// | - MAV_COMP_ID_SERVO14=153, - /// | - MAV_COMP_ID_MAPPER=180, - /// | - MAV_COMP_ID_MISSIONPLANNER=190, - /// | - MAV_COMP_ID_PATHPLANNER=195, - /// | - MAV_COMP_ID_IMU=200, - /// | - MAV_COMP_ID_IMU_2=201, - /// | - MAV_COMP_ID_IMU_3=202, - /// | - MAV_COMP_ID_GPS=220, - /// | - MAV_COMP_ID_UDP_BRIDGE=240, - /// | - MAV_COMP_ID_UART_BRIDGE=241, - /// | - MAV_COMP_ID_SYSTEM_CONTROL=250, - /// | - ENUM_END=251, - + /// | + MAV_COMP_ID_ALL = 0, + /// | + MAV_COMP_ID_CAMERA = 100, + /// | + MAV_COMP_ID_SERVO1 = 140, + /// | + MAV_COMP_ID_SERVO2 = 141, + /// | + MAV_COMP_ID_SERVO3 = 142, + /// | + MAV_COMP_ID_SERVO4 = 143, + /// | + MAV_COMP_ID_SERVO5 = 144, + /// | + MAV_COMP_ID_SERVO6 = 145, + /// | + MAV_COMP_ID_SERVO7 = 146, + /// | + MAV_COMP_ID_SERVO8 = 147, + /// | + MAV_COMP_ID_SERVO9 = 148, + /// | + MAV_COMP_ID_SERVO10 = 149, + /// | + MAV_COMP_ID_SERVO11 = 150, + /// | + MAV_COMP_ID_SERVO12 = 151, + /// | + MAV_COMP_ID_SERVO13 = 152, + /// | + MAV_COMP_ID_SERVO14 = 153, + /// | + MAV_COMP_ID_MAPPER = 180, + /// | + MAV_COMP_ID_MISSIONPLANNER = 190, + /// | + MAV_COMP_ID_PATHPLANNER = 195, + /// | + MAV_COMP_ID_IMU = 200, + /// | + MAV_COMP_ID_IMU_2 = 201, + /// | + MAV_COMP_ID_IMU_3 = 202, + /// | + MAV_COMP_ID_GPS = 220, + /// | + MAV_COMP_ID_UDP_BRIDGE = 240, + /// | + MAV_COMP_ID_UART_BRIDGE = 241, + /// | + MAV_COMP_ID_SYSTEM_CONTROL = 250, + /// | + ENUM_END = 251, + }; - + /** @brief */ public enum MAV_FRAME { - /// Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | - GLOBAL=0, - /// Local coordinate frame, Z-up (x: north, y: east, z: down). | - LOCAL_NED=1, - /// NOT a coordinate frame, indicates a mission command. | - MISSION=2, - /// Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | - GLOBAL_RELATIVE_ALT=3, - /// Local coordinate frame, Z-down (x: east, y: north, z: up) | - LOCAL_ENU=4, - /// | - ENUM_END=5, - + /// Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | + GLOBAL = 0, + /// Local coordinate frame, Z-up (x: north, y: east, z: down). | + LOCAL_NED = 1, + /// NOT a coordinate frame, indicates a mission command. | + MISSION = 2, + /// Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | + GLOBAL_RELATIVE_ALT = 3, + /// Local coordinate frame, Z-down (x: east, y: north, z: up) | + LOCAL_ENU = 4, + /// | + ENUM_END = 5, + }; - + /** @brief */ public enum MAVLINK_DATA_STREAM_TYPE { - /// | - MAVLINK_DATA_STREAM_IMG_JPEG=1, - /// | - MAVLINK_DATA_STREAM_IMG_BMP=2, - /// | - MAVLINK_DATA_STREAM_IMG_RAW8U=3, - /// | - MAVLINK_DATA_STREAM_IMG_RAW32U=4, - /// | - MAVLINK_DATA_STREAM_IMG_PGM=5, - /// | - MAVLINK_DATA_STREAM_IMG_PNG=6, - /// | - ENUM_END=7, - + /// | + MAVLINK_DATA_STREAM_IMG_JPEG = 1, + /// | + MAVLINK_DATA_STREAM_IMG_BMP = 2, + /// | + MAVLINK_DATA_STREAM_IMG_RAW8U = 3, + /// | + MAVLINK_DATA_STREAM_IMG_RAW32U = 4, + /// | + MAVLINK_DATA_STREAM_IMG_PGM = 5, + /// | + MAVLINK_DATA_STREAM_IMG_PNG = 6, + /// | + ENUM_END = 7, + }; - + /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */ public enum MAV_DATA_STREAM { - /// Enable all data streams | - ALL=0, - /// Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | - RAW_SENSORS=1, - /// Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | - EXTENDED_STATUS=2, - /// Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | - RC_CHANNELS=3, - /// Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | - RAW_CONTROLLER=4, - /// Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | - POSITION=6, - /// Dependent on the autopilot | - EXTRA1=10, - /// Dependent on the autopilot | - EXTRA2=11, - /// Dependent on the autopilot | - EXTRA3=12, - /// | - ENUM_END=13, - + /// Enable all data streams | + ALL = 0, + /// Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | + RAW_SENSORS = 1, + /// Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | + EXTENDED_STATUS = 2, + /// Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | + RC_CHANNELS = 3, + /// Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | + RAW_CONTROLLER = 4, + /// Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | + POSITION = 6, + /// Dependent on the autopilot | + EXTRA1 = 10, + /// Dependent on the autopilot | + EXTRA2 = 11, + /// Dependent on the autopilot | + EXTRA3 = 12, + /// | + ENUM_END = 13, + }; - + /** @brief The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI). */ public enum MAV_ROI { - /// No region of interest. | - NONE=0, - /// Point toward next MISSION. | - WPNEXT=1, - /// Point toward given MISSION. | - WPINDEX=2, - /// Point toward fixed location. | - LOCATION=3, - /// Point toward of given id. | - TARGET=4, - /// | - ENUM_END=5, - + /// No region of interest. | + NONE = 0, + /// Point toward next MISSION. | + WPNEXT = 1, + /// Point toward given MISSION. | + WPINDEX = 2, + /// Point toward fixed location. | + LOCATION = 3, + /// Point toward of given id. | + TARGET = 4, + /// | + ENUM_END = 5, + }; - + /** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ public enum MAV_CMD_ACK { - /// Command / mission item is ok. | - OK=1, - /// Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | - ERR_FAIL=2, - /// The system is refusing to accept this command from this source / communication partner. | - ERR_ACCESS_DENIED=3, - /// Command or mission item is not supported, other commands would be accepted. | - ERR_NOT_SUPPORTED=4, - /// The coordinate frame of this command / mission item is not supported. | - ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, - /// The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | - ERR_COORDINATES_OUT_OF_RANGE=6, - /// The X or latitude value is out of range. | - ERR_X_LAT_OUT_OF_RANGE=7, - /// The Y or longitude value is out of range. | - ERR_Y_LON_OUT_OF_RANGE=8, - /// The Z or altitude value is out of range. | - ERR_Z_ALT_OUT_OF_RANGE=9, - /// | - ENUM_END=10, - + /// Command / mission item is ok. | + OK = 1, + /// Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | + ERR_FAIL = 2, + /// The system is refusing to accept this command from this source / communication partner. | + ERR_ACCESS_DENIED = 3, + /// Command or mission item is not supported, other commands would be accepted. | + ERR_NOT_SUPPORTED = 4, + /// The coordinate frame of this command / mission item is not supported. | + ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5, + /// The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | + ERR_COORDINATES_OUT_OF_RANGE = 6, + /// The X or latitude value is out of range. | + ERR_X_LAT_OUT_OF_RANGE = 7, + /// The Y or longitude value is out of range. | + ERR_Y_LON_OUT_OF_RANGE = 8, + /// The Z or altitude value is out of range. | + ERR_Z_ALT_OUT_OF_RANGE = 9, + /// | + ENUM_END = 10, + }; - + /** @brief result from a mavlink command */ public enum MAV_RESULT { - /// Command ACCEPTED and EXECUTED | - ACCEPTED=0, - /// Command TEMPORARY REJECTED/DENIED | - TEMPORARILY_REJECTED=1, - /// Command PERMANENTLY DENIED | - DENIED=2, - /// Command UNKNOWN/UNSUPPORTED | - UNSUPPORTED=3, - /// Command executed, but failed | - FAILED=4, - /// | - ENUM_END=5, - + /// Command ACCEPTED and EXECUTED | + ACCEPTED = 0, + /// Command TEMPORARY REJECTED/DENIED | + TEMPORARILY_REJECTED = 1, + /// Command PERMANENTLY DENIED | + DENIED = 2, + /// Command UNKNOWN/UNSUPPORTED | + UNSUPPORTED = 3, + /// Command executed, but failed | + FAILED = 4, + /// | + ENUM_END = 5, + }; - + /** @brief result in a mavlink mission ack */ public enum MAV_MISSION_RESULT { - /// mission accepted OK | - MAV_MISSION_ACCEPTED=0, - /// generic error / not accepting mission commands at all right now | - MAV_MISSION_ERROR=1, - /// coordinate frame is not supported | - MAV_MISSION_UNSUPPORTED_FRAME=2, - /// command is not supported | - MAV_MISSION_UNSUPPORTED=3, - /// mission item exceeds storage space | - MAV_MISSION_NO_SPACE=4, - /// one of the parameters has an invalid value | - MAV_MISSION_INVALID=5, - /// param1 has an invalid value | - MAV_MISSION_INVALID_PARAM1=6, - /// param2 has an invalid value | - MAV_MISSION_INVALID_PARAM2=7, - /// param3 has an invalid value | - MAV_MISSION_INVALID_PARAM3=8, - /// param4 has an invalid value | - MAV_MISSION_INVALID_PARAM4=9, - /// x/param5 has an invalid value | - MAV_MISSION_INVALID_PARAM5_X=10, - /// y/param6 has an invalid value | - MAV_MISSION_INVALID_PARAM6_Y=11, - /// param7 has an invalid value | - MAV_MISSION_INVALID_PARAM7=12, - /// received waypoint out of sequence | - MAV_MISSION_INVALID_SEQUENCE=13, - /// not accepting any mission commands from this communication partner | - MAV_MISSION_DENIED=14, - /// | - ENUM_END=15, - + /// mission accepted OK | + MAV_MISSION_ACCEPTED = 0, + /// generic error / not accepting mission commands at all right now | + MAV_MISSION_ERROR = 1, + /// coordinate frame is not supported | + MAV_MISSION_UNSUPPORTED_FRAME = 2, + /// command is not supported | + MAV_MISSION_UNSUPPORTED = 3, + /// mission item exceeds storage space | + MAV_MISSION_NO_SPACE = 4, + /// one of the parameters has an invalid value | + MAV_MISSION_INVALID = 5, + /// param1 has an invalid value | + MAV_MISSION_INVALID_PARAM1 = 6, + /// param2 has an invalid value | + MAV_MISSION_INVALID_PARAM2 = 7, + /// param3 has an invalid value | + MAV_MISSION_INVALID_PARAM3 = 8, + /// param4 has an invalid value | + MAV_MISSION_INVALID_PARAM4 = 9, + /// x/param5 has an invalid value | + MAV_MISSION_INVALID_PARAM5_X = 10, + /// y/param6 has an invalid value | + MAV_MISSION_INVALID_PARAM6_Y = 11, + /// param7 has an invalid value | + MAV_MISSION_INVALID_PARAM7 = 12, + /// received waypoint out of sequence | + MAV_MISSION_INVALID_SEQUENCE = 13, + /// not accepting any mission commands from this communication partner | + MAV_MISSION_DENIED = 14, + /// | + ENUM_END = 15, + }; - + /** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ public enum MAV_SEVERITY { - /// System is unusable. This is a "panic" condition. | - EMERGENCY=0, - /// Action should be taken immediately. Indicates error in non-critical systems. | - ALERT=1, - /// Action must be taken immediately. Indicates failure in a primary system. | - CRITICAL=2, - /// Indicates an error in secondary/redundant systems. | - ERROR=3, - /// Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | - WARNING=4, - /// An unusual event has occured, though not an error condition. This should be investigated for the root cause. | - NOTICE=5, - /// Normal operational messages. Useful for logging. No action is required for these messages. | - INFO=6, - /// Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | - DEBUG=7, - /// | - ENUM_END=8, - + /// System is unusable. This is a "panic" condition. | + EMERGENCY = 0, + /// Action should be taken immediately. Indicates error in non-critical systems. | + ALERT = 1, + /// Action must be taken immediately. Indicates failure in a primary system. | + CRITICAL = 2, + /// Indicates an error in secondary/redundant systems. | + ERROR = 3, + /// Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | + WARNING = 4, + /// An unusual event has occured, though not an error condition. This should be investigated for the root cause. | + NOTICE = 5, + /// Normal operational messages. Useful for logging. No action is required for these messages. | + INFO = 6, + /// Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | + DEBUG = 7, + /// | + ENUM_END = 8, + }; - - public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - public struct mavlink_sensor_offsets_t - { - /// magnetic declination (radians) - public Single mag_declination; + + public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 42)] + public struct mavlink_sensor_offsets_t + { + /// magnetic declination (radians) + public Single mag_declination; /// raw pressure from barometer - public Int32 raw_press; + public Int32 raw_press; /// raw temperature from barometer - public Int32 raw_temp; + public Int32 raw_temp; /// gyro X calibration - public Single gyro_cal_x; + public Single gyro_cal_x; /// gyro Y calibration - public Single gyro_cal_y; + public Single gyro_cal_y; /// gyro Z calibration - public Single gyro_cal_z; + public Single gyro_cal_z; /// accel X calibration - public Single accel_cal_x; + public Single accel_cal_x; /// accel Y calibration - public Single accel_cal_y; + public Single accel_cal_y; /// accel Z calibration - public Single accel_cal_z; + public Single accel_cal_z; /// magnetometer X offset - public Int16 mag_ofs_x; + public Int16 mag_ofs_x; /// magnetometer Y offset - public Int16 mag_ofs_y; + public Int16 mag_ofs_y; /// magnetometer Z offset - public Int16 mag_ofs_z; - - }; + public Int16 mag_ofs_z; + + }; - public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - public struct mavlink_set_mag_offsets_t - { - /// magnetometer X offset - public Int16 mag_ofs_x; + public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + public struct mavlink_set_mag_offsets_t + { + /// magnetometer X offset + public Int16 mag_ofs_x; /// magnetometer Y offset - public Int16 mag_ofs_y; + public Int16 mag_ofs_y; /// magnetometer Z offset - public Int16 mag_ofs_z; + public Int16 mag_ofs_z; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MEMINFO = 152; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - public struct mavlink_meminfo_t - { - /// heap top - public UInt16 brkval; + public const byte MAVLINK_MSG_ID_MEMINFO = 152; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + public struct mavlink_meminfo_t + { + /// heap top + public UInt16 brkval; /// free memory - public UInt16 freemem; - - }; + public UInt16 freemem; + + }; - public const byte MAVLINK_MSG_ID_AP_ADC = 153; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - public struct mavlink_ap_adc_t - { - /// ADC output 1 - public UInt16 adc1; + public const byte MAVLINK_MSG_ID_AP_ADC = 153; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + public struct mavlink_ap_adc_t + { + /// ADC output 1 + public UInt16 adc1; /// ADC output 2 - public UInt16 adc2; + public UInt16 adc2; /// ADC output 3 - public UInt16 adc3; + public UInt16 adc3; /// ADC output 4 - public UInt16 adc4; + public UInt16 adc4; /// ADC output 5 - public UInt16 adc5; + public UInt16 adc5; /// ADC output 6 - public UInt16 adc6; - - }; + public UInt16 adc6; + + }; - public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - public struct mavlink_digicam_configure_t - { - /// Correspondent value to given extra_param - public Single extra_value; + public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 15)] + public struct mavlink_digicam_configure_t + { + /// Correspondent value to given extra_param + public Single extra_value; /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore) - public UInt16 shutter_speed; + public UInt16 shutter_speed; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) - public byte mode; + public byte mode; /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) - public byte aperture; + public byte aperture; /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) - public byte iso; + public byte iso; /// Exposure type enumeration from 1 to N (0 means ignore) - public byte exposure_type; + public byte exposure_type; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - public byte command_id; + public byte command_id; /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - public byte engine_cut_off; + public byte engine_cut_off; /// Extra parameters enumeration (0 means ignore) - public byte extra_param; - - }; + public byte extra_param; + + }; - public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] - public struct mavlink_digicam_control_t - { - /// Correspondent value to given extra_param - public Single extra_value; + public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 13)] + public struct mavlink_digicam_control_t + { + /// Correspondent value to given extra_param + public Single extra_value; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens - public byte session; + public byte session; /// 1 to N //Zoom's absolute position (0 means ignore) - public byte zoom_pos; + public byte zoom_pos; /// -100 to 100 //Zooming step value to offset zoom from the current position - public byte zoom_step; + public byte zoom_step; /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus - public byte focus_lock; + public byte focus_lock; /// 0: ignore, 1: shot or start filming - public byte shot; + public byte shot; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - public byte command_id; + public byte command_id; /// Extra parameters enumeration (0 means ignore) - public byte extra_param; - - }; + public byte extra_param; + + }; - public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - public struct mavlink_mount_configure_t - { - /// System ID - public byte target_system; + public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + public struct mavlink_mount_configure_t + { + /// System ID + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// mount operating mode (see MAV_MOUNT_MODE enum) - public byte mount_mode; + public byte mount_mode; /// (1 = yes, 0 = no) - public byte stab_roll; + public byte stab_roll; /// (1 = yes, 0 = no) - public byte stab_pitch; + public byte stab_pitch; /// (1 = yes, 0 = no) - public byte stab_yaw; - - }; + public byte stab_yaw; + + }; - public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - public struct mavlink_mount_control_t - { - /// pitch(deg*100) or lat, depending on mount mode - public Int32 input_a; + public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 15)] + public struct mavlink_mount_control_t + { + /// pitch(deg*100) or lat, depending on mount mode + public Int32 input_a; /// roll(deg*100) or lon depending on mount mode - public Int32 input_b; + public Int32 input_b; /// yaw(deg*100) or alt (in cm) depending on mount mode - public Int32 input_c; + public Int32 input_c; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) - public byte save_position; - - }; + public byte save_position; + + }; - public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - public struct mavlink_mount_status_t - { - /// pitch(deg*100) or lat, depending on mount mode - public Int32 pointing_a; + public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + public struct mavlink_mount_status_t + { + /// pitch(deg*100) or lat, depending on mount mode + public Int32 pointing_a; /// roll(deg*100) or lon depending on mount mode - public Int32 pointing_b; + public Int32 pointing_b; /// yaw(deg*100) or alt (in cm) depending on mount mode - public Int32 pointing_c; + public Int32 pointing_c; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_FENCE_POINT = 160; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - public struct mavlink_fence_point_t - { - /// Latitude of point - public Single lat; + public const byte MAVLINK_MSG_ID_FENCE_POINT = 160; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + public struct mavlink_fence_point_t + { + /// Latitude of point + public Single lat; /// Longitude of point - public Single lng; + public Single lng; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// point index (first point is 1, 0 is for return point) - public byte idx; + public byte idx; /// total number of points (for sanity checking) - public byte count; - - }; + public byte count; + + }; - public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - public struct mavlink_fence_fetch_point_t - { - /// System ID - public byte target_system; + public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + public struct mavlink_fence_fetch_point_t + { + /// System ID + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// point index (first point is 1, 0 is for return point) - public byte idx; - - }; + public byte idx; + + }; - public const byte MAVLINK_MSG_ID_FENCE_STATUS = 162; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] - public struct mavlink_fence_status_t - { - /// time of last breach in milliseconds since boot - public UInt32 breach_time; + public const byte MAVLINK_MSG_ID_FENCE_STATUS = 162; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 8)] + public struct mavlink_fence_status_t + { + /// time of last breach in milliseconds since boot + public UInt32 breach_time; /// number of fence breaches - public UInt16 breach_count; + public UInt16 breach_count; /// 0 if currently inside fence, 1 if outside - public byte breach_status; + public byte breach_status; /// last breach type (see FENCE_BREACH_* enum) - public byte breach_type; - - }; + public byte breach_type; + + }; - public const byte MAVLINK_MSG_ID_AHRS = 163; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - public struct mavlink_ahrs_t - { - /// X gyro drift estimate rad/s - public Single omegaIx; + public const byte MAVLINK_MSG_ID_AHRS = 163; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + public struct mavlink_ahrs_t + { + /// X gyro drift estimate rad/s + public Single omegaIx; /// Y gyro drift estimate rad/s - public Single omegaIy; + public Single omegaIy; /// Z gyro drift estimate rad/s - public Single omegaIz; + public Single omegaIz; /// average accel_weight - public Single accel_weight; + public Single accel_weight; /// average renormalisation value - public Single renorm_val; + public Single renorm_val; /// average error_roll_pitch value - public Single error_rp; + public Single error_rp; /// average error_yaw value - public Single error_yaw; - - }; + public Single error_yaw; + + }; - public const byte MAVLINK_MSG_ID_SIMSTATE = 164; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=44)] - public struct mavlink_simstate_t - { - /// Roll angle (rad) - public Single roll; + public const byte MAVLINK_MSG_ID_SIMSTATE = 164; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 44)] + public struct mavlink_simstate_t + { + /// Roll angle (rad) + public Single roll; /// Pitch angle (rad) - public Single pitch; + public Single pitch; /// Yaw angle (rad) - public Single yaw; + public Single yaw; /// X acceleration m/s/s - public Single xacc; + public Single xacc; /// Y acceleration m/s/s - public Single yacc; + public Single yacc; /// Z acceleration m/s/s - public Single zacc; + public Single zacc; /// Angular speed around X axis rad/s - public Single xgyro; + public Single xgyro; /// Angular speed around Y axis rad/s - public Single ygyro; + public Single ygyro; /// Angular speed around Z axis rad/s - public Single zgyro; + public Single zgyro; /// Latitude in degrees - public Single lat; + public Single lat; /// Longitude in degrees - public Single lng; - - }; + public Single lng; + + }; - public const byte MAVLINK_MSG_ID_HWSTATUS = 165; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - public struct mavlink_hwstatus_t - { - /// board voltage (mV) - public UInt16 Vcc; + public const byte MAVLINK_MSG_ID_HWSTATUS = 165; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + public struct mavlink_hwstatus_t + { + /// board voltage (mV) + public UInt16 Vcc; /// I2C error count - public byte I2Cerr; - - }; + public byte I2Cerr; + + }; - public const byte MAVLINK_MSG_ID_RADIO = 166; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - public struct mavlink_radio_t - { - /// receive errors - public UInt16 rxerrors; + public const byte MAVLINK_MSG_ID_RADIO = 166; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + public struct mavlink_radio_t + { + /// receive errors + public UInt16 rxerrors; /// count of error corrected packets - public UInt16 fixedp; + public UInt16 fixedp; /// local signal strength - public byte rssi; + public byte rssi; /// remote signal strength - public byte remrssi; + public byte remrssi; /// how full the tx buffer is as a percentage - public byte txbuf; + public byte txbuf; /// background noise level - public byte noise; + public byte noise; /// remote background noise level - public byte remnoise; - - }; + public byte remnoise; + + }; - public const byte MAVLINK_MSG_ID_LIMITS_STATUS = 167; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - public struct mavlink_limits_status_t - { - /// time of last breach in milliseconds since boot - public UInt32 last_trigger; + public const byte MAVLINK_MSG_ID_LIMITS_STATUS = 167; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + public struct mavlink_limits_status_t + { + /// time of last breach in milliseconds since boot + public UInt32 last_trigger; /// time of last recovery action in milliseconds since boot - public UInt32 last_action; + public UInt32 last_action; /// time of last successful recovery in milliseconds since boot - public UInt32 last_recovery; + public UInt32 last_recovery; /// time of last all-clear in milliseconds since boot - public UInt32 last_clear; + public UInt32 last_clear; /// number of fence breaches - public UInt16 breach_count; + public UInt16 breach_count; /// state of AP_Limits, (see enum LimitState, LIMITS_STATE) - public byte limits_state; + public byte limits_state; /// AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) - public byte mods_enabled; + public byte mods_enabled; /// AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) - public byte mods_required; + public byte mods_required; /// AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) - public byte mods_triggered; - - }; + public byte mods_triggered; + + }; - public const byte MAVLINK_MSG_ID_WIND = 168; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - public struct mavlink_wind_t - { - /// wind direction (degrees) - public Single direction; + public const byte MAVLINK_MSG_ID_WIND = 168; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + public struct mavlink_wind_t + { + /// wind direction (degrees) + public Single direction; /// wind speed in ground plane (m/s) - public Single speed; + public Single speed; /// vertical wind speed (m/s) - public Single speed_z; - - }; + public Single speed_z; + + }; - public const byte MAVLINK_MSG_ID_HEARTBEAT = 0; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - public struct mavlink_heartbeat_t - { - /// A bitfield for use for autopilot-specific flags. - public UInt32 custom_mode; + public const byte MAVLINK_MSG_ID_HEARTBEAT = 0; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + public struct mavlink_heartbeat_t + { + /// A bitfield for use for autopilot-specific flags. + public UInt32 custom_mode; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - public byte type; + public byte type; /// Autopilot type / class. defined in MAV_AUTOPILOT ENUM - public byte autopilot; + public byte autopilot; /// System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - public byte base_mode; + public byte base_mode; /// System status flag, see MAV_STATE ENUM - public byte system_status; + public byte system_status; /// MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - public byte mavlink_version; - - }; + public byte mavlink_version; + + }; - public const byte MAVLINK_MSG_ID_SYS_STATUS = 1; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)] - public struct mavlink_sys_status_t - { - /// Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - public UInt32 onboard_control_sensors_present; + public const byte MAVLINK_MSG_ID_SYS_STATUS = 1; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 31)] + public struct mavlink_sys_status_t + { + /// Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + public UInt32 onboard_control_sensors_present; /// Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - public UInt32 onboard_control_sensors_enabled; + public UInt32 onboard_control_sensors_enabled; /// Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control - public UInt32 onboard_control_sensors_health; + public UInt32 onboard_control_sensors_health; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - public UInt16 load; + public UInt16 load; /// Battery voltage, in millivolts (1 = 1 millivolt) - public UInt16 voltage_battery; + public UInt16 voltage_battery; /// Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - public Int16 current_battery; + public Int16 current_battery; /// Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - public UInt16 drop_rate_comm; + public UInt16 drop_rate_comm; /// Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - public UInt16 errors_comm; + public UInt16 errors_comm; /// Autopilot-specific errors - public UInt16 errors_count1; + public UInt16 errors_count1; /// Autopilot-specific errors - public UInt16 errors_count2; + public UInt16 errors_count2; /// Autopilot-specific errors - public UInt16 errors_count3; + public UInt16 errors_count3; /// Autopilot-specific errors - public UInt16 errors_count4; + public UInt16 errors_count4; /// Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - public byte battery_remaining; - - }; + public byte battery_remaining; + + }; - public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - public struct mavlink_system_time_t - { - /// Timestamp of the master clock in microseconds since UNIX epoch. - public UInt64 time_unix_usec; + public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + public struct mavlink_system_time_t + { + /// Timestamp of the master clock in microseconds since UNIX epoch. + public UInt64 time_unix_usec; /// Timestamp of the component clock since boot time in milliseconds. - public UInt32 time_boot_ms; - - }; + public UInt32 time_boot_ms; + + }; - public const byte MAVLINK_MSG_ID_PING = 4; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - public struct mavlink_ping_t - { - /// Unix timestamp in microseconds - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_PING = 4; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + public struct mavlink_ping_t + { + /// Unix timestamp in microseconds + public UInt64 time_usec; /// PING sequence - public UInt32 seq; + public UInt32 seq; /// 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 - public byte target_system; + public byte target_system; /// 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - public struct mavlink_change_operator_control_t - { - /// System the GCS requests control for - public byte target_system; + public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + public struct mavlink_change_operator_control_t + { + /// System the GCS requests control for + public byte target_system; /// 0: request control of this MAV, 1: Release control of this MAV - public byte control_request; + public byte control_request; /// 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. - public byte version; + 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 "!?,.-" - [MarshalAs(UnmanagedType.ByValArray,SizeConst=25)] - public byte[] passkey; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 25)] + public byte[] passkey; + + }; - public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - public struct mavlink_change_operator_control_ack_t - { - /// ID of the GCS this message - public byte gcs_system_id; + public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + public struct mavlink_change_operator_control_ack_t + { + /// ID of the GCS this message + public byte gcs_system_id; /// 0: request control of this MAV, 1: Release control of this MAV - public byte control_request; + public byte control_request; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - public byte ack; - - }; + public byte ack; + + }; - public const byte MAVLINK_MSG_ID_AUTH_KEY = 7; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - public struct mavlink_auth_key_t - { - /// key - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] key; - - }; + public const byte MAVLINK_MSG_ID_AUTH_KEY = 7; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + public struct mavlink_auth_key_t + { + /// key + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 32)] + public byte[] key; + + }; - public const byte MAVLINK_MSG_ID_SET_MODE = 11; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - public struct mavlink_set_mode_t - { - /// The new autopilot-specific mode. This field can be ignored by an autopilot. - public UInt32 custom_mode; + public const byte MAVLINK_MSG_ID_SET_MODE = 11; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + public struct mavlink_set_mode_t + { + /// The new autopilot-specific mode. This field can be ignored by an autopilot. + public UInt32 custom_mode; /// The system setting the mode - public byte target_system; + public byte target_system; /// The new base mode - public byte base_mode; - - }; + public byte base_mode; + + }; - public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - public struct mavlink_param_request_read_t - { - /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - public Int16 param_index; + public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + public struct mavlink_param_request_read_t + { + /// Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + public Int16 param_index; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 16)] + public byte[] param_id; + + }; - public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - public struct mavlink_param_request_list_t - { - /// System ID - public byte target_system; + public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + public struct mavlink_param_request_list_t + { + /// System ID + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)] - public struct mavlink_param_value_t - { - /// Onboard parameter value - public Single param_value; + public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 25)] + public struct mavlink_param_value_t + { + /// Onboard parameter value + public Single param_value; /// Total number of onboard parameters - public UInt16 param_count; + public UInt16 param_count; /// Index of this onboard parameter - public UInt16 param_index; + public UInt16 param_index; /// Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 16)] + public byte[] param_id; /// Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h - public byte param_type; - - }; + public byte param_type; + + }; - public const byte MAVLINK_MSG_ID_PARAM_SET = 23; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] - public struct mavlink_param_set_t - { - /// Onboard parameter value - public Single param_value; + public const byte MAVLINK_MSG_ID_PARAM_SET = 23; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 23)] + public struct mavlink_param_set_t + { + /// Onboard parameter value + public Single param_value; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)] - public byte[] param_id; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 16)] + public byte[] param_id; /// Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h - public byte param_type; - - }; + public byte param_type; + + }; - public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 24; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] - public struct mavlink_gps_raw_int_t - { - /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 24; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 30)] + public struct mavlink_gps_raw_int_t + { + /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public UInt64 time_usec; /// Latitude in 1E7 degrees - public Int32 lat; + public Int32 lat; /// Longitude in 1E7 degrees - public Int32 lon; + public Int32 lon; /// Altitude in 1E3 meters (millimeters) above MSL - public Int32 alt; + public Int32 alt; /// GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - public UInt16 eph; + public UInt16 eph; /// GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - public UInt16 epv; + public UInt16 epv; /// GPS ground speed (m/s * 100). If unknown, set to: 65535 - public UInt16 vel; + public UInt16 vel; /// Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - public UInt16 cog; + public UInt16 cog; /// 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. - public byte fix_type; + public byte fix_type; /// Number of satellites visible. If unknown, set to 255 - public byte satellites_visible; - - }; + public byte satellites_visible; + + }; - public const byte MAVLINK_MSG_ID_GPS_STATUS = 25; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=101)] - public struct mavlink_gps_status_t - { - /// Number of satellites visible - public byte satellites_visible; + public const byte MAVLINK_MSG_ID_GPS_STATUS = 25; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 101)] + public struct mavlink_gps_status_t + { + /// Number of satellites visible + public byte satellites_visible; /// Global satellite ID - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_prn; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 20)] + public byte[] satellite_prn; /// 0: Satellite not used, 1: used for localization - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_used; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 20)] + public byte[] satellite_used; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_elevation; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 20)] + public byte[] satellite_elevation; /// Direction of satellite, 0: 0 deg, 255: 360 deg. - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_azimuth; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 20)] + public byte[] satellite_azimuth; /// Signal to noise ratio of satellite - [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)] - public byte[] satellite_snr; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 20)] + public byte[] satellite_snr; + + }; - public const byte MAVLINK_MSG_ID_SCALED_IMU = 26; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - public struct mavlink_scaled_imu_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_SCALED_IMU = 26; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + public struct mavlink_scaled_imu_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// X acceleration (mg) - public Int16 xacc; + public Int16 xacc; /// Y acceleration (mg) - public Int16 yacc; + public Int16 yacc; /// Z acceleration (mg) - public Int16 zacc; + public Int16 zacc; /// Angular speed around X axis (millirad /sec) - public Int16 xgyro; + public Int16 xgyro; /// Angular speed around Y axis (millirad /sec) - public Int16 ygyro; + public Int16 ygyro; /// Angular speed around Z axis (millirad /sec) - public Int16 zgyro; + public Int16 zgyro; /// X Magnetic field (milli tesla) - public Int16 xmag; + public Int16 xmag; /// Y Magnetic field (milli tesla) - public Int16 ymag; + public Int16 ymag; /// Z Magnetic field (milli tesla) - public Int16 zmag; - - }; + public Int16 zmag; + + }; - public const byte MAVLINK_MSG_ID_RAW_IMU = 27; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] - public struct mavlink_raw_imu_t - { - /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_RAW_IMU = 27; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 26)] + public struct mavlink_raw_imu_t + { + /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public UInt64 time_usec; /// X acceleration (raw) - public Int16 xacc; + public Int16 xacc; /// Y acceleration (raw) - public Int16 yacc; + public Int16 yacc; /// Z acceleration (raw) - public Int16 zacc; + public Int16 zacc; /// Angular speed around X axis (raw) - public Int16 xgyro; + public Int16 xgyro; /// Angular speed around Y axis (raw) - public Int16 ygyro; + public Int16 ygyro; /// Angular speed around Z axis (raw) - public Int16 zgyro; + public Int16 zgyro; /// X Magnetic field (raw) - public Int16 xmag; + public Int16 xmag; /// Y Magnetic field (raw) - public Int16 ymag; + public Int16 ymag; /// Z Magnetic field (raw) - public Int16 zmag; - - }; + public Int16 zmag; + + }; - public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 28; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)] - public struct mavlink_raw_pressure_t - { - /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 28; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 16)] + public struct mavlink_raw_pressure_t + { + /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public UInt64 time_usec; /// Absolute pressure (raw) - public Int16 press_abs; + public Int16 press_abs; /// Differential pressure 1 (raw) - public Int16 press_diff1; + public Int16 press_diff1; /// Differential pressure 2 (raw) - public Int16 press_diff2; + public Int16 press_diff2; /// Raw Temperature measurement (raw) - public Int16 temperature; - - }; + public Int16 temperature; + + }; - public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 29; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)] - public struct mavlink_scaled_pressure_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 29; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 14)] + public struct mavlink_scaled_pressure_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// Absolute pressure (hectopascal) - public Single press_abs; + public Single press_abs; /// Differential pressure 1 (hectopascal) - public Single press_diff; + public Single press_diff; /// Temperature measurement (0.01 degrees celsius) - public Int16 temperature; - - }; + public Int16 temperature; + + }; - public const byte MAVLINK_MSG_ID_ATTITUDE = 30; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - public struct mavlink_attitude_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_ATTITUDE = 30; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + public struct mavlink_attitude_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// Roll angle (rad) - public Single roll; + public Single roll; /// Pitch angle (rad) - public Single pitch; + public Single pitch; /// Yaw angle (rad) - public Single yaw; + public Single yaw; /// Roll angular speed (rad/s) - public Single rollspeed; + public Single rollspeed; /// Pitch angular speed (rad/s) - public Single pitchspeed; + public Single pitchspeed; /// Yaw angular speed (rad/s) - public Single yawspeed; - - }; + public Single yawspeed; + + }; - public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - public struct mavlink_attitude_quaternion_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + public struct mavlink_attitude_quaternion_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// Quaternion component 1 - public Single q1; + public Single q1; /// Quaternion component 2 - public Single q2; + public Single q2; /// Quaternion component 3 - public Single q3; + public Single q3; /// Quaternion component 4 - public Single q4; + public Single q4; /// Roll angular speed (rad/s) - public Single rollspeed; + public Single rollspeed; /// Pitch angular speed (rad/s) - public Single pitchspeed; + public Single pitchspeed; /// Yaw angular speed (rad/s) - public Single yawspeed; - - }; + public Single yawspeed; + + }; - public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - public struct mavlink_local_position_ned_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + public struct mavlink_local_position_ned_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// X Position - public Single x; + public Single x; /// Y Position - public Single y; + public Single y; /// Z Position - public Single z; + public Single z; /// X Speed - public Single vx; + public Single vx; /// Y Speed - public Single vy; + public Single vy; /// Z Speed - public Single vz; - - }; + public Single vz; + + }; - public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - public struct mavlink_global_position_int_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + public struct mavlink_global_position_int_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// Latitude, expressed as * 1E7 - public Int32 lat; + public Int32 lat; /// Longitude, expressed as * 1E7 - public Int32 lon; + public Int32 lon; /// Altitude in meters, expressed as * 1000 (millimeters), above MSL - public Int32 alt; + public Int32 alt; /// Altitude above ground in meters, expressed as * 1000 (millimeters) - public Int32 relative_alt; + public Int32 relative_alt; /// Ground X Speed (Latitude), expressed as m/s * 100 - public Int16 vx; + public Int16 vx; /// Ground Y Speed (Longitude), expressed as m/s * 100 - public Int16 vy; + public Int16 vy; /// Ground Z Speed (Altitude), expressed as m/s * 100 - public Int16 vz; + public Int16 vz; /// Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - public UInt16 hdg; - - }; + public UInt16 hdg; + + }; - public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - public struct mavlink_rc_channels_scaled_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + public struct mavlink_rc_channels_scaled_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan1_scaled; + public Int16 chan1_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan2_scaled; + public Int16 chan2_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan3_scaled; + public Int16 chan3_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan4_scaled; + public Int16 chan4_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan5_scaled; + public Int16 chan5_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan6_scaled; + public Int16 chan6_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan7_scaled; + public Int16 chan7_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public Int16 chan8_scaled; + public Int16 chan8_scaled; /// Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - public byte port; + public byte port; /// Receive signal strength indicator, 0: 0%, 255: 100% - public byte rssi; - - }; + public byte rssi; + + }; - public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)] - public struct mavlink_rc_channels_raw_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 22)] + public struct mavlink_rc_channels_raw_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// RC channel 1 value, in microseconds - public UInt16 chan1_raw; + public UInt16 chan1_raw; /// RC channel 2 value, in microseconds - public UInt16 chan2_raw; + public UInt16 chan2_raw; /// RC channel 3 value, in microseconds - public UInt16 chan3_raw; + public UInt16 chan3_raw; /// RC channel 4 value, in microseconds - public UInt16 chan4_raw; + public UInt16 chan4_raw; /// RC channel 5 value, in microseconds - public UInt16 chan5_raw; + public UInt16 chan5_raw; /// RC channel 6 value, in microseconds - public UInt16 chan6_raw; + public UInt16 chan6_raw; /// RC channel 7 value, in microseconds - public UInt16 chan7_raw; + public UInt16 chan7_raw; /// RC channel 8 value, in microseconds - public UInt16 chan8_raw; + public UInt16 chan8_raw; /// Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - public byte port; + public byte port; /// Receive signal strength indicator, 0: 0%, 255: 100% - public byte rssi; - - }; + public byte rssi; + + }; - public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)] - public struct mavlink_servo_output_raw_t - { - /// Timestamp (microseconds since system boot) - public UInt32 time_usec; + public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 21)] + public struct mavlink_servo_output_raw_t + { + /// Timestamp (microseconds since system boot) + public UInt32 time_usec; /// Servo output 1 value, in microseconds - public UInt16 servo1_raw; + public UInt16 servo1_raw; /// Servo output 2 value, in microseconds - public UInt16 servo2_raw; + public UInt16 servo2_raw; /// Servo output 3 value, in microseconds - public UInt16 servo3_raw; + public UInt16 servo3_raw; /// Servo output 4 value, in microseconds - public UInt16 servo4_raw; + public UInt16 servo4_raw; /// Servo output 5 value, in microseconds - public UInt16 servo5_raw; + public UInt16 servo5_raw; /// Servo output 6 value, in microseconds - public UInt16 servo6_raw; + public UInt16 servo6_raw; /// Servo output 7 value, in microseconds - public UInt16 servo7_raw; + public UInt16 servo7_raw; /// Servo output 8 value, in microseconds - public UInt16 servo8_raw; + public UInt16 servo8_raw; /// Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - public byte port; - - }; + public byte port; + + }; - public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - public struct mavlink_mission_request_partial_list_t - { - /// Start index, 0 by default - public Int16 start_index; + public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + public struct mavlink_mission_request_partial_list_t + { + /// Start index, 0 by default + public Int16 start_index; /// End index, -1 by default (-1: send list to end). Else a valid index of the list - public Int16 end_index; + public Int16 end_index; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - public struct mavlink_mission_write_partial_list_t - { - /// Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - public Int16 start_index; + public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + public struct mavlink_mission_write_partial_list_t + { + /// Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + public Int16 start_index; /// End index, equal or greater than start index. - public Int16 end_index; + public Int16 end_index; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MISSION_ITEM = 39; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)] - public struct mavlink_mission_item_t - { - /// PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters - public Single param1; + public const byte MAVLINK_MSG_ID_MISSION_ITEM = 39; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 37)] + public struct mavlink_mission_item_t + { + /// PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + public Single param1; /// PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - public Single param2; + public Single param2; /// PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. - public Single param3; + public Single param3; /// PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH - public Single param4; + public Single param4; /// PARAM5 / local: x position, global: latitude - public Single x; + public Single x; /// PARAM6 / y position: global: longitude - public Single y; + public Single y; /// PARAM7 / z position: global: altitude - public Single z; + public Single z; /// Sequence - public UInt16 seq; + public UInt16 seq; /// The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - public UInt16 command; + public UInt16 command; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - public byte frame; + public byte frame; /// false:0, true:1 - public byte current; + public byte current; /// autocontinue to next wp - public byte autocontinue; - - }; + public byte autocontinue; + + }; - public const byte MAVLINK_MSG_ID_MISSION_REQUEST = 40; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - public struct mavlink_mission_request_t - { - /// Sequence - public UInt16 seq; + public const byte MAVLINK_MSG_ID_MISSION_REQUEST = 40; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + public struct mavlink_mission_request_t + { + /// Sequence + public UInt16 seq; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - public struct mavlink_mission_set_current_t - { - /// Sequence - public UInt16 seq; + public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + public struct mavlink_mission_set_current_t + { + /// Sequence + public UInt16 seq; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MISSION_CURRENT = 42; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - public struct mavlink_mission_current_t - { - /// Sequence - public UInt16 seq; - - }; + public const byte MAVLINK_MSG_ID_MISSION_CURRENT = 42; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + public struct mavlink_mission_current_t + { + /// Sequence + public UInt16 seq; + + }; - public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - public struct mavlink_mission_request_list_t - { - /// System ID - public byte target_system; - /// Component ID - public byte target_component; - - }; - - - public const byte MAVLINK_MSG_ID_MISSION_COUNT = 44; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - public struct mavlink_mission_count_t - { - /// Number of mission items in the sequence - public UInt16 count; + public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + public struct mavlink_mission_request_list_t + { /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - public struct mavlink_mission_clear_all_t - { - /// System ID - public byte target_system; + public const byte MAVLINK_MSG_ID_MISSION_COUNT = 44; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + public struct mavlink_mission_count_t + { + /// Number of mission items in the sequence + public UInt16 count; + /// System ID + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] - public struct mavlink_mission_item_reached_t - { - /// Sequence - public UInt16 seq; - - }; - - - public const byte MAVLINK_MSG_ID_MISSION_ACK = 47; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - public struct mavlink_mission_ack_t - { - /// System ID - public byte target_system; + public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + public struct mavlink_mission_clear_all_t + { + /// System ID + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; + + }; + + + public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 2)] + public struct mavlink_mission_item_reached_t + { + /// Sequence + public UInt16 seq; + + }; + + + public const byte MAVLINK_MSG_ID_MISSION_ACK = 47; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + public struct mavlink_mission_ack_t + { + /// System ID + public byte target_system; + /// Component ID + public byte target_component; /// See MAV_MISSION_RESULT enum - public byte type; - - }; + public byte type; + + }; - public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] - public struct mavlink_set_gps_global_origin_t - { - /// global position * 1E7 - public Int32 latitude; + public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 13)] + public struct mavlink_set_gps_global_origin_t + { /// global position * 1E7 - public Int32 longitude; + public Int32 latitude; + /// global position * 1E7 + public Int32 longitude; /// global position * 1000 - public Int32 altitude; + public Int32 altitude; /// System ID - public byte target_system; - - }; + public byte target_system; + + }; - public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)] - public struct mavlink_gps_global_origin_t - { - /// Latitude (WGS84), expressed as * 1E7 - public Int32 latitude; + public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 12)] + public struct mavlink_gps_global_origin_t + { + /// Latitude (WGS84), expressed as * 1E7 + public Int32 latitude; /// Longitude (WGS84), expressed as * 1E7 - public Int32 longitude; + public Int32 longitude; /// Altitude(WGS84), expressed as * 1000 - public Int32 altitude; - - }; + public Int32 altitude; + + }; - public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)] - public struct mavlink_set_local_position_setpoint_t - { - /// x position - public Single x; + public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 19)] + public struct mavlink_set_local_position_setpoint_t + { + /// x position + public Single x; /// y position - public Single y; + public Single y; /// z position - public Single z; + public Single z; /// Desired yaw angle - public Single yaw; + public Single yaw; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - public byte coordinate_frame; - - }; + public byte coordinate_frame; + + }; - public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)] - public struct mavlink_local_position_setpoint_t - { - /// x position - public Single x; + public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 17)] + public struct mavlink_local_position_setpoint_t + { + /// x position + public Single x; /// y position - public Single y; + public Single y; /// z position - public Single z; + public Single z; /// Desired yaw angle - public Single yaw; + public Single yaw; /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - public byte coordinate_frame; - - }; + public byte coordinate_frame; + + }; - public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - public struct mavlink_global_position_setpoint_int_t - { - /// WGS84 Latitude position in degrees * 1E7 - public Int32 latitude; + public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 15)] + public struct mavlink_global_position_setpoint_int_t + { + /// WGS84 Latitude position in degrees * 1E7 + public Int32 latitude; /// WGS84 Longitude position in degrees * 1E7 - public Int32 longitude; + public Int32 longitude; /// WGS84 Altitude in meters * 1000 (positive for up) - public Int32 altitude; + public Int32 altitude; /// Desired yaw angle in degrees * 100 - public Int16 yaw; + public Int16 yaw; /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - public byte coordinate_frame; - - }; + public byte coordinate_frame; + + }; - public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)] - public struct mavlink_set_global_position_setpoint_int_t - { - /// WGS84 Latitude position in degrees * 1E7 - public Int32 latitude; + public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 15)] + public struct mavlink_set_global_position_setpoint_int_t + { + /// WGS84 Latitude position in degrees * 1E7 + public Int32 latitude; /// WGS84 Longitude position in degrees * 1E7 - public Int32 longitude; + public Int32 longitude; /// WGS84 Altitude in meters * 1000 (positive for up) - public Int32 altitude; + public Int32 altitude; /// Desired yaw angle in degrees * 100 - public Int16 yaw; + public Int16 yaw; /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - public byte coordinate_frame; - - }; + public byte coordinate_frame; + + }; - public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)] - public struct mavlink_safety_set_allowed_area_t - { - /// x position 1 / Latitude 1 - public Single p1x; + public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 27)] + public struct mavlink_safety_set_allowed_area_t + { + /// x position 1 / Latitude 1 + public Single p1x; /// y position 1 / Longitude 1 - public Single p1y; + public Single p1y; /// z position 1 / Altitude 1 - public Single p1z; + public Single p1z; /// x position 2 / Latitude 2 - public Single p2x; + public Single p2x; /// y position 2 / Longitude 2 - public Single p2y; + public Single p2y; /// z position 2 / Altitude 2 - public Single p2z; + public Single p2z; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; + public byte target_component; /// Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - public byte frame; - - }; + public byte frame; + + }; - public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)] - public struct mavlink_safety_allowed_area_t - { - /// x position 1 / Latitude 1 - public Single p1x; + public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 25)] + public struct mavlink_safety_allowed_area_t + { + /// x position 1 / Latitude 1 + public Single p1x; /// y position 1 / Longitude 1 - public Single p1y; + public Single p1y; /// z position 1 / Altitude 1 - public Single p1z; + public Single p1z; /// x position 2 / Latitude 2 - public Single p2x; + public Single p2x; /// y position 2 / Longitude 2 - public Single p2y; + public Single p2y; /// z position 2 / Altitude 2 - public Single p2z; + public Single p2z; /// Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - public byte frame; - - }; + public byte frame; + + }; - public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - public struct mavlink_set_roll_pitch_yaw_thrust_t - { - /// Desired roll angle in radians - public Single roll; - /// Desired pitch angle in radians - public Single pitch; - /// Desired yaw angle in radians - public Single yaw; - /// Collective thrust, normalized to 0 .. 1 - public Single thrust; - /// System ID - public byte target_system; - /// Component ID - public byte target_component; - - }; - - - public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - public struct mavlink_set_roll_pitch_yaw_speed_thrust_t - { - /// Desired roll angular speed in rad/s - public Single roll_speed; - /// Desired pitch angular speed in rad/s - public Single pitch_speed; - /// Desired yaw angular speed in rad/s - public Single yaw_speed; - /// Collective thrust, normalized to 0 .. 1 - public Single thrust; - /// System ID - public byte target_system; - /// Component ID - public byte target_component; - - }; - - - public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - public struct mavlink_roll_pitch_yaw_thrust_setpoint_t - { - /// Timestamp in milliseconds since system boot - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + public struct mavlink_set_roll_pitch_yaw_thrust_t + { /// Desired roll angle in radians - public Single roll; + public Single roll; /// Desired pitch angle in radians - public Single pitch; + public Single pitch; /// Desired yaw angle in radians - public Single yaw; + public Single yaw; /// Collective thrust, normalized to 0 .. 1 - public Single thrust; - - }; - - - public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - public struct mavlink_roll_pitch_yaw_speed_thrust_setpoint_t - { - /// Timestamp in milliseconds since system boot - public UInt32 time_boot_ms; - /// Desired roll angular speed in rad/s - public Single roll_speed; - /// Desired pitch angular speed in rad/s - public Single pitch_speed; - /// Desired yaw angular speed in rad/s - public Single yaw_speed; - /// Collective thrust, normalized to 0 .. 1 - public Single thrust; - - }; - - - public const byte MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT = 60; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - public struct mavlink_set_quad_motors_setpoint_t - { - /// Front motor in + configuration, front left motor in x configuration - public UInt16 motor_front_nw; - /// Right motor in + configuration, front right motor in x configuration - public UInt16 motor_right_ne; - /// Back motor in + configuration, back right motor in x configuration - public UInt16 motor_back_se; - /// Left motor in + configuration, back left motor in x configuration - public UInt16 motor_left_sw; - /// System ID of the system that should set these motor commands - public byte target_system; - - }; - - - public const byte MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST = 61; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=34)] - public struct mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t - { - /// Desired roll angle in radians +-PI (+-32767) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public Int16[] roll; - /// Desired pitch angle in radians +-PI (+-32767) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public Int16[] pitch; - /// Desired yaw angle in radians, scaled to int16 +-PI (+-32767) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public Int16[] yaw; - /// Collective thrust, scaled to uint16 (0..65535) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public UInt16[] thrust; - /// ID of the quadrotor group (0 - 255, up to 256 groups supported) - public byte group; - /// ID of the flight mode (0 - 255, up to 256 modes supported) - public byte mode; - - }; - - - public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] - public struct mavlink_nav_controller_output_t - { - /// Current desired roll in degrees - public Single nav_roll; - /// Current desired pitch in degrees - public Single nav_pitch; - /// Current altitude error in meters - public Single alt_error; - /// Current airspeed error in meters/second - public Single aspd_error; - /// Current crosstrack error on x-y plane in meters - public Single xtrack_error; - /// Current desired heading in degrees - public Int16 nav_bearing; - /// Bearing to current MISSION/target in degrees - public Int16 target_bearing; - /// Distance to active MISSION in meters - public UInt16 wp_dist; - - }; - - - public const byte MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST = 63; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=46)] - public struct mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t - { - /// Desired roll angle in radians +-PI (+-32767) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public Int16[] roll; - /// Desired pitch angle in radians +-PI (+-32767) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public Int16[] pitch; - /// Desired yaw angle in radians, scaled to int16 +-PI (+-32767) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public Int16[] yaw; - /// Collective thrust, scaled to uint16 (0..65535) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public UInt16[] thrust; - /// ID of the quadrotor group (0 - 255, up to 256 groups supported) - public byte group; - /// ID of the flight mode (0 - 255, up to 256 modes supported) - public byte mode; - /// RGB red channel (0-255) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] led_red; - /// RGB green channel (0-255) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] led_blue; - /// RGB blue channel (0-255) - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public byte[] led_green; - - }; - - - public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)] - public struct mavlink_state_correction_t - { - /// x position error - public Single xErr; - /// y position error - public Single yErr; - /// z position error - public Single zErr; - /// roll error (radians) - public Single rollErr; - /// pitch error (radians) - public Single pitchErr; - /// yaw error (radians) - public Single yawErr; - /// x velocity - public Single vxErr; - /// y velocity - public Single vyErr; - /// z velocity - public Single vzErr; - - }; - - - public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] - public struct mavlink_request_data_stream_t - { - /// The requested interval between two messages of this type - public UInt16 req_message_rate; - /// The target requested to send the message stream. - public byte target_system; - /// The target requested to send the message stream. - public byte target_component; - /// The ID of the requested data stream - public byte req_stream_id; - /// 1 to start sending, 0 to stop sending. - public byte start_stop; - - }; - - - public const byte MAVLINK_MSG_ID_DATA_STREAM = 67; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)] - public struct mavlink_data_stream_t - { - /// The requested interval between two messages of this type - public UInt16 message_rate; - /// The ID of the requested data stream - public byte stream_id; - /// 1 stream is enabled, 0 stream is stopped. - public byte on_off; - - }; - - - public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)] - public struct mavlink_manual_control_t - { - /// roll - public Single roll; - /// pitch - public Single pitch; - /// yaw - public Single yaw; - /// thrust - public Single thrust; - /// The system to be controlled - public byte target; - /// roll control enabled auto:0, manual:1 - public byte roll_manual; - /// pitch auto:0, manual:1 - public byte pitch_manual; - /// yaw auto:0, manual:1 - public byte yaw_manual; - /// thrust auto:0, manual:1 - public byte thrust_manual; - - }; - - - public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - public struct mavlink_rc_channels_override_t - { - /// RC channel 1 value, in microseconds - public UInt16 chan1_raw; - /// RC channel 2 value, in microseconds - public UInt16 chan2_raw; - /// RC channel 3 value, in microseconds - public UInt16 chan3_raw; - /// RC channel 4 value, in microseconds - public UInt16 chan4_raw; - /// RC channel 5 value, in microseconds - public UInt16 chan5_raw; - /// RC channel 6 value, in microseconds - public UInt16 chan6_raw; - /// RC channel 7 value, in microseconds - public UInt16 chan7_raw; - /// RC channel 8 value, in microseconds - public UInt16 chan8_raw; + public Single thrust; /// System ID - public byte target_system; + public byte target_system; /// Component ID - public byte target_component; - - }; + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_VFR_HUD = 74; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - public struct mavlink_vfr_hud_t - { - /// Current airspeed in m/s - public Single airspeed; - /// Current ground speed in m/s - public Single groundspeed; - /// Current altitude (MSL), in meters - public Single alt; - /// Current climb rate in meters/second - public Single climb; - /// Current heading in degrees, in compass units (0..360, 0=north) - public Int16 heading; - /// Current throttle setting in integer percent, 0 to 100 - public UInt16 throttle; - - }; + public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + public struct mavlink_set_roll_pitch_yaw_speed_thrust_t + { + /// Desired roll angular speed in rad/s + public Single roll_speed; + /// Desired pitch angular speed in rad/s + public Single pitch_speed; + /// Desired yaw angular speed in rad/s + public Single yaw_speed; + /// Collective thrust, normalized to 0 .. 1 + public Single thrust; + /// System ID + public byte target_system; + /// Component ID + public byte target_component; + + }; - public const byte MAVLINK_MSG_ID_COMMAND_LONG = 76; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] - public struct mavlink_command_long_t - { - /// Parameter 1, as defined by MAV_CMD enum. - public Single param1; - /// Parameter 2, as defined by MAV_CMD enum. - public Single param2; - /// Parameter 3, as defined by MAV_CMD enum. - public Single param3; - /// Parameter 4, as defined by MAV_CMD enum. - public Single param4; - /// Parameter 5, as defined by MAV_CMD enum. - public Single param5; - /// Parameter 6, as defined by MAV_CMD enum. - public Single param6; - /// Parameter 7, as defined by MAV_CMD enum. - public Single param7; - /// Command ID, as defined by MAV_CMD enum. - public UInt16 command; - /// System which should execute the command - public byte target_system; - /// Component which should execute the command, 0 for all components - public byte target_component; - /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - public byte confirmation; - - }; + public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + public struct mavlink_roll_pitch_yaw_thrust_setpoint_t + { + /// Timestamp in milliseconds since system boot + public UInt32 time_boot_ms; + /// Desired roll angle in radians + public Single roll; + /// Desired pitch angle in radians + public Single pitch; + /// Desired yaw angle in radians + public Single yaw; + /// Collective thrust, normalized to 0 .. 1 + public Single thrust; + + }; - public const byte MAVLINK_MSG_ID_COMMAND_ACK = 77; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)] - public struct mavlink_command_ack_t - { - /// Command ID, as defined by MAV_CMD enum. - public UInt16 command; - /// See MAV_RESULT enum - public byte result; - - }; + public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + public struct mavlink_roll_pitch_yaw_speed_thrust_setpoint_t + { + /// Timestamp in milliseconds since system boot + public UInt32 time_boot_ms; + /// Desired roll angular speed in rad/s + public Single roll_speed; + /// Desired pitch angular speed in rad/s + public Single pitch_speed; + /// Desired yaw angular speed in rad/s + public Single yaw_speed; + /// Collective thrust, normalized to 0 .. 1 + public Single thrust; + + }; - public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)] - public struct mavlink_local_position_ned_system_global_offset_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; - /// X Position - public Single x; - /// Y Position - public Single y; - /// Z Position - public Single z; - /// Roll - public Single roll; - /// Pitch - public Single pitch; - /// Yaw - public Single yaw; - - }; + public const byte MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT = 60; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + public struct mavlink_set_quad_motors_setpoint_t + { + /// Front motor in + configuration, front left motor in x configuration + public UInt16 motor_front_nw; + /// Right motor in + configuration, front right motor in x configuration + public UInt16 motor_right_ne; + /// Back motor in + configuration, back right motor in x configuration + public UInt16 motor_back_se; + /// Left motor in + configuration, back left motor in x configuration + public UInt16 motor_left_sw; + /// System ID of the system that should set these motor commands + public byte target_system; + + }; - public const byte MAVLINK_MSG_ID_HIL_STATE = 90; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=56)] - public struct mavlink_hil_state_t - { - /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public UInt64 time_usec; - /// Roll angle (rad) - public Single roll; - /// Pitch angle (rad) - public Single pitch; - /// Yaw angle (rad) - public Single yaw; - /// Roll angular speed (rad/s) - public Single rollspeed; - /// Pitch angular speed (rad/s) - public Single pitchspeed; - /// Yaw angular speed (rad/s) - public Single yawspeed; - /// Latitude, expressed as * 1E7 - public Int32 lat; - /// Longitude, expressed as * 1E7 - public Int32 lon; - /// Altitude in meters, expressed as * 1000 (millimeters) - public Int32 alt; - /// Ground X Speed (Latitude), expressed as m/s * 100 - public Int16 vx; - /// Ground Y Speed (Longitude), expressed as m/s * 100 - public Int16 vy; - /// Ground Z Speed (Altitude), expressed as m/s * 100 - public Int16 vz; - /// X acceleration (mg) - public Int16 xacc; - /// Y acceleration (mg) - public Int16 yacc; - /// Z acceleration (mg) - public Int16 zacc; - - }; + public const byte MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST = 61; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 34)] + public struct mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t + { + /// Desired roll angle in radians +-PI (+-32767) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public Int16[] roll; + /// Desired pitch angle in radians +-PI (+-32767) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public Int16[] pitch; + /// Desired yaw angle in radians, scaled to int16 +-PI (+-32767) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public Int16[] yaw; + /// Collective thrust, scaled to uint16 (0..65535) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public UInt16[] thrust; + /// ID of the quadrotor group (0 - 255, up to 256 groups supported) + public byte group; + /// ID of the flight mode (0 - 255, up to 256 modes supported) + public byte mode; + + }; - public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 91; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] - public struct mavlink_hil_controls_t - { - /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public UInt64 time_usec; - /// Control output -1 .. 1 - public Single roll_ailerons; - /// Control output -1 .. 1 - public Single pitch_elevator; - /// Control output -1 .. 1 - public Single yaw_rudder; - /// Throttle 0 .. 1 - public Single throttle; - /// Aux 1, -1 .. 1 - public Single aux1; - /// Aux 2, -1 .. 1 - public Single aux2; - /// Aux 3, -1 .. 1 - public Single aux3; - /// Aux 4, -1 .. 1 - public Single aux4; - /// System mode (MAV_MODE) - public byte mode; - /// Navigation mode (MAV_NAV_MODE) - public byte nav_mode; - - }; + public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 26)] + public struct mavlink_nav_controller_output_t + { + /// Current desired roll in degrees + public Single nav_roll; + /// Current desired pitch in degrees + public Single nav_pitch; + /// Current altitude error in meters + public Single alt_error; + /// Current airspeed error in meters/second + public Single aspd_error; + /// Current crosstrack error on x-y plane in meters + public Single xtrack_error; + /// Current desired heading in degrees + public Int16 nav_bearing; + /// Bearing to current MISSION/target in degrees + public Int16 target_bearing; + /// Distance to active MISSION in meters + public UInt16 wp_dist; + + }; - public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] - public struct mavlink_hil_rc_inputs_raw_t - { - /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST = 63; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 46)] + public struct mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t + { + /// Desired roll angle in radians +-PI (+-32767) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public Int16[] roll; + /// Desired pitch angle in radians +-PI (+-32767) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public Int16[] pitch; + /// Desired yaw angle in radians, scaled to int16 +-PI (+-32767) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public Int16[] yaw; + /// Collective thrust, scaled to uint16 (0..65535) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public UInt16[] thrust; + /// ID of the quadrotor group (0 - 255, up to 256 groups supported) + public byte group; + /// ID of the flight mode (0 - 255, up to 256 modes supported) + public byte mode; + /// RGB red channel (0-255) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public byte[] led_red; + /// RGB green channel (0-255) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public byte[] led_blue; + /// RGB blue channel (0-255) + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)] + public byte[] led_green; + + }; + + + public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)] + public struct mavlink_state_correction_t + { + /// x position error + public Single xErr; + /// y position error + public Single yErr; + /// z position error + public Single zErr; + /// roll error (radians) + public Single rollErr; + /// pitch error (radians) + public Single pitchErr; + /// yaw error (radians) + public Single yawErr; + /// x velocity + public Single vxErr; + /// y velocity + public Single vyErr; + /// z velocity + public Single vzErr; + + }; + + + public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 6)] + public struct mavlink_request_data_stream_t + { + /// The requested interval between two messages of this type + public UInt16 req_message_rate; + /// The target requested to send the message stream. + public byte target_system; + /// The target requested to send the message stream. + public byte target_component; + /// The ID of the requested data stream + public byte req_stream_id; + /// 1 to start sending, 0 to stop sending. + public byte start_stop; + + }; + + + public const byte MAVLINK_MSG_ID_DATA_STREAM = 67; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 4)] + public struct mavlink_data_stream_t + { + /// The requested interval between two messages of this type + public UInt16 message_rate; + /// The ID of the requested data stream + public byte stream_id; + /// 1 stream is enabled, 0 stream is stopped. + public byte on_off; + + }; + + + public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 21)] + public struct mavlink_manual_control_t + { + /// roll + public Single roll; + /// pitch + public Single pitch; + /// yaw + public Single yaw; + /// thrust + public Single thrust; + /// The system to be controlled + public byte target; + /// roll control enabled auto:0, manual:1 + public byte roll_manual; + /// pitch auto:0, manual:1 + public byte pitch_manual; + /// yaw auto:0, manual:1 + public byte yaw_manual; + /// thrust auto:0, manual:1 + public byte thrust_manual; + + }; + + + public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + public struct mavlink_rc_channels_override_t + { /// RC channel 1 value, in microseconds - public UInt16 chan1_raw; + public UInt16 chan1_raw; /// RC channel 2 value, in microseconds - public UInt16 chan2_raw; + public UInt16 chan2_raw; /// RC channel 3 value, in microseconds - public UInt16 chan3_raw; + public UInt16 chan3_raw; /// RC channel 4 value, in microseconds - public UInt16 chan4_raw; + public UInt16 chan4_raw; /// RC channel 5 value, in microseconds - public UInt16 chan5_raw; + public UInt16 chan5_raw; /// RC channel 6 value, in microseconds - public UInt16 chan6_raw; + public UInt16 chan6_raw; /// RC channel 7 value, in microseconds - public UInt16 chan7_raw; + public UInt16 chan7_raw; /// RC channel 8 value, in microseconds - public UInt16 chan8_raw; + public UInt16 chan8_raw; + /// System ID + public byte target_system; + /// Component ID + public byte target_component; + + }; + + + public const byte MAVLINK_MSG_ID_VFR_HUD = 74; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + public struct mavlink_vfr_hud_t + { + /// Current airspeed in m/s + public Single airspeed; + /// Current ground speed in m/s + public Single groundspeed; + /// Current altitude (MSL), in meters + public Single alt; + /// Current climb rate in meters/second + public Single climb; + /// Current heading in degrees, in compass units (0..360, 0=north) + public Int16 heading; + /// Current throttle setting in integer percent, 0 to 100 + public UInt16 throttle; + + }; + + + public const byte MAVLINK_MSG_ID_COMMAND_LONG = 76; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 33)] + public struct mavlink_command_long_t + { + /// Parameter 1, as defined by MAV_CMD enum. + public Single param1; + /// Parameter 2, as defined by MAV_CMD enum. + public Single param2; + /// Parameter 3, as defined by MAV_CMD enum. + public Single param3; + /// Parameter 4, as defined by MAV_CMD enum. + public Single param4; + /// Parameter 5, as defined by MAV_CMD enum. + public Single param5; + /// Parameter 6, as defined by MAV_CMD enum. + public Single param6; + /// Parameter 7, as defined by MAV_CMD enum. + public Single param7; + /// Command ID, as defined by MAV_CMD enum. + public UInt16 command; + /// System which should execute the command + public byte target_system; + /// Component which should execute the command, 0 for all components + public byte target_component; + /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + public byte confirmation; + + }; + + + public const byte MAVLINK_MSG_ID_COMMAND_ACK = 77; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 3)] + public struct mavlink_command_ack_t + { + /// Command ID, as defined by MAV_CMD enum. + public UInt16 command; + /// See MAV_RESULT enum + public byte result; + + }; + + + public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 28)] + public struct mavlink_local_position_ned_system_global_offset_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; + /// X Position + public Single x; + /// Y Position + public Single y; + /// Z Position + public Single z; + /// Roll + public Single roll; + /// Pitch + public Single pitch; + /// Yaw + public Single yaw; + + }; + + + public const byte MAVLINK_MSG_ID_HIL_STATE = 90; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 56)] + public struct mavlink_hil_state_t + { + /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public UInt64 time_usec; + /// Roll angle (rad) + public Single roll; + /// Pitch angle (rad) + public Single pitch; + /// Yaw angle (rad) + public Single yaw; + /// Roll angular speed (rad/s) + public Single rollspeed; + /// Pitch angular speed (rad/s) + public Single pitchspeed; + /// Yaw angular speed (rad/s) + public Single yawspeed; + /// Latitude, expressed as * 1E7 + public Int32 lat; + /// Longitude, expressed as * 1E7 + public Int32 lon; + /// Altitude in meters, expressed as * 1000 (millimeters) + public Int32 alt; + /// Ground X Speed (Latitude), expressed as m/s * 100 + public Int16 vx; + /// Ground Y Speed (Longitude), expressed as m/s * 100 + public Int16 vy; + /// Ground Z Speed (Altitude), expressed as m/s * 100 + public Int16 vz; + /// X acceleration (mg) + public Int16 xacc; + /// Y acceleration (mg) + public Int16 yacc; + /// Z acceleration (mg) + public Int16 zacc; + + }; + + + public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 91; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 42)] + public struct mavlink_hil_controls_t + { + /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public UInt64 time_usec; + /// Control output -1 .. 1 + public Single roll_ailerons; + /// Control output -1 .. 1 + public Single pitch_elevator; + /// Control output -1 .. 1 + public Single yaw_rudder; + /// Throttle 0 .. 1 + public Single throttle; + /// Aux 1, -1 .. 1 + public Single aux1; + /// Aux 2, -1 .. 1 + public Single aux2; + /// Aux 3, -1 .. 1 + public Single aux3; + /// Aux 4, -1 .. 1 + public Single aux4; + /// System mode (MAV_MODE) + public byte mode; + /// Navigation mode (MAV_NAV_MODE) + public byte nav_mode; + + }; + + + public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 33)] + public struct mavlink_hil_rc_inputs_raw_t + { + /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public UInt64 time_usec; + /// RC channel 1 value, in microseconds + public UInt16 chan1_raw; + /// RC channel 2 value, in microseconds + public UInt16 chan2_raw; + /// RC channel 3 value, in microseconds + public UInt16 chan3_raw; + /// RC channel 4 value, in microseconds + public UInt16 chan4_raw; + /// RC channel 5 value, in microseconds + public UInt16 chan5_raw; + /// RC channel 6 value, in microseconds + public UInt16 chan6_raw; + /// RC channel 7 value, in microseconds + public UInt16 chan7_raw; + /// RC channel 8 value, in microseconds + public UInt16 chan8_raw; /// RC channel 9 value, in microseconds - public UInt16 chan9_raw; + public UInt16 chan9_raw; /// RC channel 10 value, in microseconds - public UInt16 chan10_raw; + public UInt16 chan10_raw; /// RC channel 11 value, in microseconds - public UInt16 chan11_raw; + public UInt16 chan11_raw; /// RC channel 12 value, in microseconds - public UInt16 chan12_raw; + public UInt16 chan12_raw; /// Receive signal strength indicator, 0: 0%, 255: 100% - public byte rssi; - - }; + public byte rssi; + + }; - public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)] - public struct mavlink_optical_flow_t - { - /// Timestamp (UNIX) - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 26)] + public struct mavlink_optical_flow_t + { + /// Timestamp (UNIX) + public UInt64 time_usec; /// Flow in meters in x-sensor direction, angular-speed compensated - public Single flow_comp_m_x; + public Single flow_comp_m_x; /// Flow in meters in y-sensor direction, angular-speed compensated - public Single flow_comp_m_y; + public Single flow_comp_m_y; /// Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - public Single ground_distance; + public Single ground_distance; /// Flow in pixels in x-sensor direction - public Int16 flow_x; + public Int16 flow_x; /// Flow in pixels in y-sensor direction - public Int16 flow_y; + public Int16 flow_y; /// Sensor ID - public byte sensor_id; + public byte sensor_id; /// Optical flow quality / confidence. 0: bad, 255: maximum quality - public byte quality; - - }; + public byte quality; + + }; - public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - public struct mavlink_global_vision_position_estimate_t - { - /// Timestamp (milliseconds) - public UInt64 usec; + public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + public struct mavlink_global_vision_position_estimate_t + { + /// Timestamp (milliseconds) + public UInt64 usec; /// Global X position - public Single x; + public Single x; /// Global Y position - public Single y; + public Single y; /// Global Z position - public Single z; + public Single z; /// Roll angle in rad - public Single roll; + public Single roll; /// Pitch angle in rad - public Single pitch; + public Single pitch; /// Yaw angle in rad - public Single yaw; - - }; + public Single yaw; + + }; - public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - public struct mavlink_vision_position_estimate_t - { - /// Timestamp (milliseconds) - public UInt64 usec; + public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + public struct mavlink_vision_position_estimate_t + { + /// Timestamp (milliseconds) + public UInt64 usec; /// Global X position - public Single x; + public Single x; /// Global Y position - public Single y; + public Single y; /// Global Z position - public Single z; + public Single z; /// Roll angle in rad - public Single roll; + public Single roll; /// Pitch angle in rad - public Single pitch; + public Single pitch; /// Yaw angle in rad - public Single yaw; - - }; + public Single yaw; + + }; - public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)] - public struct mavlink_vision_speed_estimate_t - { - /// Timestamp (milliseconds) - public UInt64 usec; + public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 20)] + public struct mavlink_vision_speed_estimate_t + { + /// Timestamp (milliseconds) + public UInt64 usec; /// Global X speed - public Single x; + public Single x; /// Global Y speed - public Single y; + public Single y; /// Global Z speed - public Single z; - - }; + public Single z; + + }; - public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - public struct mavlink_vicon_position_estimate_t - { - /// Timestamp (milliseconds) - public UInt64 usec; + public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 32)] + public struct mavlink_vicon_position_estimate_t + { + /// Timestamp (milliseconds) + public UInt64 usec; /// Global X position - public Single x; + public Single x; /// Global Y position - public Single y; + public Single y; /// Global Z position - public Single z; + public Single z; /// Roll angle in rad - public Single roll; + public Single roll; /// Pitch angle in rad - public Single pitch; + public Single pitch; /// Yaw angle in rad - public Single yaw; - - }; + public Single yaw; + + }; - public const byte MAVLINK_MSG_ID_MEMORY_VECT = 249; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)] - public struct mavlink_memory_vect_t - { - /// Starting address of the debug variables - public UInt16 address; + public const byte MAVLINK_MSG_ID_MEMORY_VECT = 249; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 36)] + public struct mavlink_memory_vect_t + { + /// Starting address of the debug variables + public UInt16 address; /// Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - public byte ver; + 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 - public byte type; + public byte type; /// Memory contents at specified address - [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] - public byte[] value; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 32)] + public byte[] value; + + }; - public const byte MAVLINK_MSG_ID_DEBUG_VECT = 250; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)] - public struct mavlink_debug_vect_t - { - /// Timestamp - public UInt64 time_usec; + public const byte MAVLINK_MSG_ID_DEBUG_VECT = 250; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 30)] + public struct mavlink_debug_vect_t + { + /// Timestamp + public UInt64 time_usec; /// x - public Single x; + public Single x; /// y - public Single y; + public Single y; /// z - public Single z; + public Single z; /// Name - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 10)] + public byte[] name; + + }; - public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - public struct mavlink_named_value_float_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + public struct mavlink_named_value_float_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// Floating point value - public Single value; + public Single value; /// Name of the debug variable - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 10)] + public byte[] name; + + }; - public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 252; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)] - public struct mavlink_named_value_int_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 252; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 18)] + public struct mavlink_named_value_int_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// Signed integer value - public Int32 value; + public Int32 value; /// Name of the debug variable - [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)] - public byte[] name; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 10)] + public byte[] name; + + }; - public const byte MAVLINK_MSG_ID_STATUSTEXT = 253; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)] - public struct mavlink_statustext_t - { - /// Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - public byte severity; + public const byte MAVLINK_MSG_ID_STATUSTEXT = 253; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 51)] + public struct mavlink_statustext_t + { + /// Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + public byte severity; /// Status text message, without null termination character - [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] - public byte[] text; - - }; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 50)] + public byte[] text; + + }; - public const byte MAVLINK_MSG_ID_DEBUG = 254; - [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] - public struct mavlink_debug_t - { - /// Timestamp (milliseconds since system boot) - public UInt32 time_boot_ms; + public const byte MAVLINK_MSG_ID_DEBUG = 254; + [StructLayout(LayoutKind.Sequential, Pack = 1, Size = 9)] + public struct mavlink_debug_t + { + /// Timestamp (milliseconds since system boot) + public UInt32 time_boot_ms; /// DEBUG value - public Single value; + public Single value; /// index of debug variable - public byte ind; - - }; + public byte ind; - } - #endif + }; + + } } diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index d9e9478490..8c52639e37 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -1333,6 +1333,8 @@ namespace ArdupilotMega foreach (string logfile in openFileDialog1.FileNames) { + int wplists = 0; + MAVLink mine = new MAVLink(); try { @@ -1344,17 +1346,28 @@ namespace ArdupilotMega mine.packets.Initialize(); // clear - StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".txt"); + while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length) + { + // bar moves to 100 % in this step + progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f); - // bar moves to 100 % in this step - progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f); + progressBar1.Refresh(); + //Application.DoEvents(); + byte count = 0; + try + { + count = mine.getWPCount(); + } + catch { } - progressBar1.Refresh(); - //Application.DoEvents(); + if (count == 0) + { + continue; + } - sw.WriteLine("QGC WPL 110"); + StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile) + Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + "-" + wplists + ".txt"); - byte count = mine.getWPCount(); + sw.WriteLine("QGC WPL 110"); for (ushort a = 0; a < count; a++) { Locationwp wp = mine.getWP(a); @@ -1375,8 +1388,10 @@ namespace ArdupilotMega sw.Write("\t" + 1); sw.WriteLine(""); } - - sw.Close(); + + sw.Close(); + wplists++; + } progressBar1.Value = 100; diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs index 81c5c160fb..d2af21e514 100644 --- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs +++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs @@ -2,14 +2,14 @@ - + - - + + @@ -31,7 +31,7 @@ - + @@ -61,197 +61,201 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + - - - - - - - - - - + + + + + + + + + + - - - - - + + + + + - - - - + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - + + + + - - - - - - - - - + + + + + + + + + - - - - - - - + + + + + + + - - - + + + - - - + + + - - - + + + - - - + + + - - - - + + + + - - - - - - - + + + + + + + - - - + + + - - - - + + + + - - - + + + - - - + + + - - - + + + @@ -295,26 +299,26 @@ - - - + + - - - - - - - + + + + + + - - - - - + + + + + + + diff --git a/Tools/ArdupilotMegaPlanner/OpenGLtest.cs b/Tools/ArdupilotMegaPlanner/OpenGLtest.cs index 5e7a43599a..972cb2414e 100644 --- a/Tools/ArdupilotMegaPlanner/OpenGLtest.cs +++ b/Tools/ArdupilotMegaPlanner/OpenGLtest.cs @@ -253,6 +253,8 @@ namespace ArdupilotMega.Controls sw.Start(); + zoom = 11; + getImage(); sw.Stop(); @@ -261,7 +263,7 @@ namespace ArdupilotMega.Controls sw.Start(); - double increment = step * 1; + double increment = step * 5; double cleanup = area.Bottom % increment; double cleanup2 = area.Left % increment; @@ -274,12 +276,12 @@ namespace ArdupilotMega.Controls { int heightl = srtm.getAltitude(z, area.Right + area.Left - x, 20); - // Console.WriteLine(x + " " + z); + // Console.WriteLine(x + " " + z); GL.Color3(Color.White); - // int heightl = 0; + // int heightl = 0; double scale2 = (Math.Abs(x - area.Left) / area.WidthLng);// / (float)_terrain.Width; diff --git a/Tools/ArdupilotMegaPlanner/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs index 38f6b127ef..746d7f18c3 100644 --- a/Tools/ArdupilotMegaPlanner/Program.cs +++ b/Tools/ArdupilotMegaPlanner/Program.cs @@ -38,7 +38,10 @@ namespace ArdupilotMega //Common.linearRegression(); - //Console.WriteLine(srtm.getAltitude(-35.115676879882812, 117.94178754638671,20)); + Console.WriteLine(srtm.getAltitude(-35.115676879882812, 117.94178754638671,20)); + + // Console.ReadLine(); + // return; /* Arduino.ArduinoSTKv2 comport = new Arduino.ArduinoSTKv2(); diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index baf34ed7c2..aa1334753d 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.1.*")] -[assembly: AssemblyFileVersion("1.2.12")] +[assembly: AssemblyFileVersion("1.2.13")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/ResEdit.cs b/Tools/ArdupilotMegaPlanner/ResEdit.cs index 5a1baced21..5adc5a79f4 100644 --- a/Tools/ArdupilotMegaPlanner/ResEdit.cs +++ b/Tools/ArdupilotMegaPlanner/ResEdit.cs @@ -251,7 +251,7 @@ namespace resedit try { - thisAssembly = Assembly.LoadFile(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + ci + Path.DirectorySeparatorChar + "ArdupilotMegaPlanner.resources.dll"); + thisAssembly = Assembly.LoadFile(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + ci + Path.DirectorySeparatorChar + "ArdupilotMegaPlanner10.resources.dll"); } catch { return; } diff --git a/Tools/ArdupilotMegaPlanner/dataflashlog.xml b/Tools/ArdupilotMegaPlanner/dataflashlog.xml index 7dcb55c71e..b02da6f24d 100644 --- a/Tools/ArdupilotMegaPlanner/dataflashlog.xml +++ b/Tools/ArdupilotMegaPlanner/dataflashlog.xml @@ -20,8 +20,6 @@ Yaw IN Yaw Nav Yaw - Roll I - Pitch I WP Dist @@ -32,20 +30,16 @@ Nav Roll X Speed Y Speed - Nav Lon I - Nav Lat I - Thr in + Thr IN Sonar Alt Baro Alt WP Alt Nav Throttle - Angle Boost + Angle boost Climb Rate Throttle Out - Alt Hold Int - Thr iInt Gyro Saturation diff --git a/Tools/ArdupilotMegaPlanner/srtm.cs b/Tools/ArdupilotMegaPlanner/srtm.cs index 6efa01b991..96bc6ff7f3 100644 --- a/Tools/ArdupilotMegaPlanner/srtm.cs +++ b/Tools/ArdupilotMegaPlanner/srtm.cs @@ -27,19 +27,21 @@ namespace ArdupilotMega static Hashtable filecache = new Hashtable(); + static Dictionary cache = new Dictionary(); + public static int getAltitude(double lat, double lng, double zoom) { short alt = 0; - lat += 1 / 1199.0; + //lat += 1 / 1199.0; //lng -= 1 / 1201f; // lat -35.115676879882812 double // lng 117.94178754638671 double // alt 70 short - int x = (int)Math.Floor(lng); - int y = (int)Math.Floor(lat); + int x = (lng < 0) ? (int)(lng-1) : (int)lng;//(int)Math.Floor(lng); + int y = (lat < 0) ? (int)(lat - 1) : (int)lat; ;//(int)Math.Floor(lat); string ns; if (y > 0) @@ -63,47 +65,65 @@ namespace ArdupilotMega try { - if (filecache.ContainsKey(datadirectory + Path.DirectorySeparatorChar + filename) || File.Exists(datadirectory + Path.DirectorySeparatorChar + filename)) + if (cache.ContainsKey(filename) || File.Exists(datadirectory + Path.DirectorySeparatorChar + filename)) { // srtm hgt files - //FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open, FileAccess.Read, FileShare.Read); - MemoryStream fs = readFile(datadirectory + Path.DirectorySeparatorChar + filename); + int size = -1; + + if (!cache.ContainsKey(filename)) + { + FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open, FileAccess.Read, FileShare.Read); + + if (fs.Length == (1201 * 1201 * 2)) + { + size = 1201; + } + else + { + size = 3601; + } + + byte[] altbytes = new byte[2]; + short[,] altdata = new short[size, size]; + + + int altlat = 0; + int altlng = 0; + + while (fs.Read(altbytes, 0, 2) != 0) + { + altdata[altlat, altlng] = (short)((altbytes[0] << 8) + altbytes[1]); + + altlat++; + if (altlat >= size) + { + altlng++; + altlat = 0; + } + } + + fs.Close(); + + cache[filename] = altdata; + } + + if (cache[filename].Length == (1201 * 1201)) + { + size = 1201; + } + else + { + size = 3601; + } int posx = 0; int row = 0; - if (fs.Length <= (1201 * 1201 * 2)) - { - posx = (int)(((float)(lng - x)) * (1201 * 2)); - row = (int)(((float)(lat - y)) * 1201) * (1201 * 2); - row = (1201 * 1201 * 2) - row; - } - else - { - posx = (int)(((float)(lng - x)) * (3601 * 2)); - row = (int)(((float)(lat - y)) * 3601) * (3601 * 2); - row = (3601 * 3601 * 2) - row; - } + posx = (int)(((float)(lng - x)) * (size * 1)); + row = (int)(((float)(lat - y)) * (size * 1)); + row = size - row; - if (posx % 2 == 1) - { - posx--; - } - - //Console.WriteLine(filename + " row " + row + " posx" + posx); - - byte[] data = new byte[2]; - - fs.Seek((int)(row + posx), SeekOrigin.Begin); - fs.Read(data, 0, data.Length); - - //fs.Close(); - - //Array.Reverse(data); - - alt = (short)((data[0] << 8) + data[1]) ;//BitConverter.ToInt16(data, 0); - - return alt; + return cache[filename][posx, row]; } string filename2 = "srtm_" + Math.Round((lng + 2.5 + 180) / 5, 0).ToString("00") + "_" + Math.Round((60 - lat + 2.5) / 5, 0).ToString("00") + ".asc"; diff --git a/Tools/ArdupilotMegaPlanner/temp.Designer.cs b/Tools/ArdupilotMegaPlanner/temp.Designer.cs index 903c1d4f5c..129b6afca8 100644 --- a/Tools/ArdupilotMegaPlanner/temp.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/temp.Designer.cs @@ -249,7 +249,7 @@ // this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; - this.ClientSize = new System.Drawing.Size(685, 285); + this.ClientSize = new System.Drawing.Size(685, 507); this.Controls.Add(this.myButton1); this.Controls.Add(this.BUT_paramgen); this.Controls.Add(this.BUT_follow_me); diff --git a/Tools/ArdupilotMegaPlanner/temp.cs b/Tools/ArdupilotMegaPlanner/temp.cs index 1686e14479..876854790d 100644 --- a/Tools/ArdupilotMegaPlanner/temp.cs +++ b/Tools/ArdupilotMegaPlanner/temp.cs @@ -31,11 +31,11 @@ namespace ArdupilotMega if (System.Diagnostics.Debugger.IsAttached) { - // ArdupilotMega.Controls.OpenGLtest ogl = new Controls.OpenGLtest(); + ArdupilotMega.Controls.OpenGLtest ogl = new Controls.OpenGLtest(); - // this.Controls.Add(ogl); + this.Controls.Add(ogl); - // ogl.Dock = DockStyle.Fill; + ogl.Dock = DockStyle.Fill; } }